Skip to content

Commit b0b64cf

Browse files
shrijitsingh99nevalsar
authored andcommitted
Add guide for setting up and using MapViz in ROS2
1 parent c8481f7 commit b0b64cf

File tree

2 files changed

+354
-0
lines changed

2 files changed

+354
-0
lines changed

_data/navigation.yml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -307,6 +307,8 @@ wiki:
307307
url: /wiki/tools/stream-rviz/
308308
- title: Web-Based Visualization using ROS JavaScript Library
309309
url: /wiki/tools/roslibjs/
310+
- title: MapViz for Map Based Visualization in ROS2
311+
url: /wiki/planning/mapviz/
310312
- title: Gazebo Simulation
311313
url: /wiki/tools/gazebo-simulation/
312314
- title: Code Editors - Introduction to VS Code and Vim

wiki/tools/mapviz.md

Lines changed: 352 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,352 @@
1+
# MapViz for Map Based Visualization in ROS2
2+
3+
Mapviz is a highly customizable ROS-based visualization tool focused on large-scale 2D data, with a plugin system for extreme extensibility. Mapviz is similar to Rviz, but is specifically designed for 2D, top-down viewing of outdoor robots, especially in overlaying data on an external map from OpenStreetMaps or Google maps.
4+
5+
This tutorial will explain how to setup Mapviz for ROS2 along with Google Maps satellite view.
6+
7+
## Setting up Mapviz
8+
A setup guide is provided in the official [website](https://swri-robotics.github.io/mapviz/). This assumes you already have a version of ROS2 installed along with a colcon workspace.
9+
10+
MapViz can be installed directly from apt using the following commands:
11+
```bash
12+
sudo apt-get install ros-$ROS_DISTRO-mapviz \
13+
ros-$ROS_DISTRO-mapviz-plugins \
14+
ros-$ROS_DISTRO-tile-map \
15+
ros-$ROS_DISTRO-multires-image
16+
```
17+
18+
In case, its not available or you need to build it from source, you can do so with the following steps:
19+
20+
1. Clone the latest version of the repository using the most recent branch into your `src` folder inside your workspace. At the time of writing the latest branch was `ros2-devel`.
21+
```bash
22+
git clone -b ros2-devel https://github.com/swri-robotics/mapviz.git
23+
```
24+
2. Build the workspace
25+
```bash
26+
colcon build --symlink-install --packages-select mapviz_interfaces mapviz mapviz_plugins tile_map multires_image
27+
```
28+
29+
## Setting up Google Maps Satellite
30+
This part of the tutorial uses the following repo [GitHub - danielsnider/MapViz-Tile-Map-Google-Maps-Satellite: ROS Offline Google Maps for MapViz](https://github.com/danielsnider/MapViz-Tile-Map-Google-Maps-Satellite) to proxy Google Maps satellite view into a WMTS tile service so that it can be viewed on Mapviz.
31+
32+
The following are the steps to set it up, such that this service autostart on boot.
33+
34+
1. Install Docker
35+
```bash
36+
sudo apt install docker.io
37+
sudo systemctl enable --now docker
38+
sudo groupadd docker
39+
sudo usermod -aG docker $USER
40+
```
41+
After running these commands log out and log back into your user account.
42+
43+
2. Setup the proxy
44+
```bash
45+
sudo docker run -p 8080:8080 -d -t --restart=always danielsnider/mapproxy
46+
```
47+
48+
**Note:**
49+
1. The ‘—restart=always’ argument will make the container always run in the background even after reboots
50+
2. This will bind to port 80 which might be needed for other applications especially during web development
51+
52+
3. Setup Custom Source
53+
54+
Launch Mapviz
55+
```bash
56+
ros2 launch mapviz mapviz.launch.py
57+
```
58+
59+
1. You can then add a new layer to the map by clicking on the add button on the bottom left corner of the map.
60+
2. Add a new `map_tile` display component
61+
3. In the `Source` dropdown select `Custom WMTS source`
62+
4. Set the `Base URL` to `http://localhost:8080/wmts/gm_layer/gm_grid/{level}/{x}/{y}.png`
63+
5. Set the 'Max Zoom' to 19
64+
6. Click `Save`
65+
66+
The map should now load up with Google Maps satellite view. This may take some time initally.
67+
68+
## Advanced Setup
69+
70+
1. Create a custom launch file
71+
You can create a custom launch file to load Mapviz with a custom configuration and initalize to a custom origin by default.
72+
73+
```python
74+
import launch
75+
from launch.actions import DeclareLaunchArgument
76+
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
77+
from launch_ros.actions import Node
78+
from launch_ros.substitutions import FindPackageShare
79+
80+
81+
def generate_launch_description():
82+
current_pkg = FindPackageShare('your_package_name')
83+
84+
return launch.LaunchDescription(
85+
[
86+
DeclareLaunchArgument(
87+
'mapviz_config',
88+
default_value=PathJoinSubstitution([current_pkg, 'mapviz', 'mapviz.mvc']),
89+
description='Full path to the Mapviz config file to use',
90+
),
91+
Node(
92+
package='mapviz',
93+
executable='mapviz',
94+
name='mapviz',
95+
output={'both': 'log'},
96+
parameters=[
97+
{'config': LaunchConfiguration('mapviz_config'), 'autosave': False}
98+
],
99+
),
100+
Node(
101+
package='mapviz',
102+
executable='initialize_origin.py',
103+
name='initialize_origin',
104+
parameters=[
105+
{'local_xy_frame': 'map'},
106+
{'local_xy_navsatfix_topic': 'gps/fix/origin'},
107+
{'local_xy_origin': 'auto'},
108+
{
109+
'local_xy_origins': """[
110+
{'name': 'pitt',
111+
'latitude': 40.438889608527084,
112+
'longitude': -79.95833630855975,
113+
'altitude': 273.1324935602024,
114+
'heading': 0.0}
115+
]"""
116+
},
117+
],
118+
),
119+
]
120+
)
121+
```
122+
123+
This will find the share directory of your package. This generally where all configs are stored for ROS2 packages.
124+
125+
```python
126+
current_pkg = FindPackageShare('your_package_name')
127+
```
128+
129+
Using this we can load the custom Mapviz config. This line assumes by default the config file is stored in the `mapviz` folder of your package and is named `mapviz.mvc`.
130+
```python
131+
DeclareLaunchArgument(
132+
'mapviz_config',
133+
default_value=PathJoinSubstitution([current_pkg, 'mapviz', 'mapviz.mvc']),
134+
description='Full path to the Mapviz config file to use',
135+
),
136+
```
137+
138+
This will load the Mapviz node with the custom config file and ensure that autosave is disabled.
139+
```python
140+
Node(
141+
package='mapviz',
142+
executable='mapviz',
143+
name='mapviz',
144+
output={'both': 'log'},
145+
parameters=[
146+
{'config': LaunchConfiguration('mapviz_config'), 'autosave': False}
147+
],
148+
),
149+
```
150+
151+
This will load the `initialize_origin.py` node which will initialize the origin of the map to the specified location. This is useful if you want to start the map at a specific location or using your current GPS location.
152+
153+
By setting local_xy_origin to `auto` it will use the current GPS location as the origin. For this to work you need to have a GPS sensor publishing the origin GPS coordinate to the topic `gps/fix/origin` with the message type `sensor_msgs/msg/NavSatFix`.
154+
155+
Incase you want to set the origin to a specific location you can set the `local_xy_origin` to the name of the origin you want to use. This name should match the name of the origin in the `local_xy_origins` parameter.
156+
For this example we will set the origin to the name `pitt` which is the name of the origin in the `local_xy_origins` parameter. This sets it to a specific location in Pittsburgh, PA.
157+
158+
```python
159+
Node(
160+
package='mapviz',
161+
executable='initialize_origin.py',
162+
name='initialize_origin',
163+
parameters=[
164+
{'local_xy_frame': 'map'},
165+
{'local_xy_navsatfix_topic': 'gps/fix/origin'},
166+
{'local_xy_origin': 'auto'},
167+
{
168+
'local_xy_origins': """[
169+
{'name': 'pitt',
170+
'latitude': 40.438889608527084,
171+
'longitude': -79.95833630855975,
172+
'altitude': 273.1324935602024,
173+
'heading': 0.0}
174+
]"""
175+
},
176+
],
177+
)
178+
```
179+
180+
2. Setting the origin to the current GPS location
181+
182+
The following script subscribes the current GPS location and re-publishes the first GPS coordinate it recieves as the origin on the topic `gps/fix/origin`.
183+
184+
Incase you are using the `robot_localization` package to fuse GPS, it also calls the `SetDatum` service offered by the `robot_localization` package to set the datum of the robot_localization node.
185+
This is necessary to ensure that the robot_localization node is using the same origin as the one used by Mapviz.
186+
187+
You will need to run this script before running Mapviz. This can be done by adding it to the `launch` file of your package or by running it manually.
188+
189+
```python
190+
#!/usr/bin/env python3
191+
192+
import rclpy
193+
from rclpy.node import Node
194+
from rclpy.qos import (
195+
qos_profile_sensor_data,
196+
QoSDurabilityPolicy,
197+
QoSHistoryPolicy,
198+
QoSProfile,
199+
)
200+
201+
from robot_localization.srv import SetDatum
202+
from sensor_msgs.msg import NavSatFix, NavSatStatus
203+
204+
205+
class GpsDatum(Node):
206+
"""
207+
Republishes the first valid gps fix and sets datum in robot_localization.
208+
209+
Subscribes and stores the first valid gps fix, then republishes it as the
210+
origin. Also calls SetDatum service offered by robot_localization.
211+
212+
"""
213+
214+
def __init__(self):
215+
super().__init__('gps_datum')
216+
217+
self.gps_datm_msg_ = None
218+
self.rl_datum_future_ = None
219+
self.rl_datum_set_ = False
220+
221+
self.sub_gps_ = self.create_subscription(
222+
NavSatFix, 'gps/fix', self.sub_gps_cb, qos_profile_sensor_data
223+
)
224+
225+
self.pub_gps_datum_ = self.create_publisher(
226+
NavSatFix,
227+
'gps/fix/origin',
228+
QoSProfile(
229+
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
230+
history=QoSHistoryPolicy.KEEP_LAST,
231+
depth=1,
232+
),
233+
)
234+
235+
# Need to use a timer since latching behaviour doesn't behave like ROS1
236+
# https://github.com/ros2/ros2/issues/464
237+
timer_period_ = 1.0
238+
self.timer_ = self.create_timer(timer_period_, self.timer_callback)
239+
240+
self.rl_datum_client = self.create_client(SetDatum, 'datum')
241+
self.get_logger().info('Waiting for robot_localization datum service')
242+
self.rl_datum_client.wait_for_service()
243+
self.get_logger().info('robot_localization datum service now available')
244+
245+
def sub_gps_cb(self, msg):
246+
if msg.status.status == NavSatStatus.STATUS_NO_FIX:
247+
return
248+
self.gps_datm_msg_ = msg
249+
self.get_logger().info('Successfully set origin. Unsubscribing to gps fix')
250+
self.destroy_subscription(self.sub_gps_)
251+
252+
def timer_callback(self):
253+
if self.gps_datm_msg_ is None:
254+
return
255+
self.pub_gps_datum_.publish(self.gps_datm_msg_)
256+
self.send_rl_request()
257+
258+
def send_rl_request(self):
259+
if self.rl_datum_set_ or self.gps_datm_msg_ is None:
260+
return
261+
262+
if self.rl_datum_future_ is None:
263+
req = SetDatum.Request()
264+
req.geo_pose.position.latitude = self.gps_datm_msg_.latitude
265+
req.geo_pose.position.longitude = self.gps_datm_msg_.longitude
266+
req.geo_pose.position.altitude = self.gps_datm_msg_.altitude
267+
req.geo_pose.orientation.w = 1.0
268+
self.get_logger().info(
269+
'Sending request to SetDatum request to robot_localization'
270+
)
271+
self.rl_datum_future_ = self.rl_datum_client.call_async(req)
272+
else:
273+
if self.rl_datum_future_.done():
274+
try:
275+
self.rl_datum_future_.result()
276+
except Exception as e: # noqa: B902
277+
self.get_logger().info(
278+
'Call to SetDatum service in robot_localization failed %r'
279+
% (e,)
280+
)
281+
else:
282+
self.get_logger().info('Datum set in robot_localization')
283+
self.rl_datum_set_ = True
284+
285+
286+
def main(args=None):
287+
rclpy.init(args=args)
288+
289+
gps_datum = GpsDatum()
290+
291+
rclpy.spin(gps_datum)
292+
293+
gps_datum.destroy_node()
294+
rclpy.shutdown()
295+
296+
297+
if __name__ == '__main__':
298+
main()
299+
```
300+
301+
3. Custom Configuration
302+
303+
Below is an example configuration file mentioned above as `mapviz.mvc` for Mapviz. This loads the Google Maps Satellite layer and shows the GPS location published on the `/gps/fix` topic.
304+
305+
```
306+
capture_directory: "~"
307+
fixed_frame: map
308+
target_frame: <none>
309+
fix_orientation: false
310+
rotate_90: true
311+
enable_antialiasing: true
312+
show_displays: true
313+
show_status_bar: true
314+
show_capture_tools: true
315+
window_width: 1848
316+
window_height: 1016
317+
view_scale: 0.09229598
318+
offset_x: 0
319+
offset_y: 0
320+
use_latest_transforms: true
321+
background: "#a0a0a4"
322+
image_transport: raw
323+
displays:
324+
- type: mapviz_plugins/tile_map
325+
name: Map
326+
config:
327+
visible: true
328+
collapsed: true
329+
custom_sources:
330+
- base_url: http://localhost:8080/wmts/gm_layer/gm_grid/{level}/{x}/{y}.png
331+
max_zoom: 19
332+
name: GMaps
333+
type: wmts
334+
- base_url: https://tile.openstreetmap.org/{level}/{x}/{y}.png
335+
max_zoom: 19
336+
name: OSM
337+
type: wmts
338+
bing_api_key: ""
339+
source: GMaps
340+
- type: mapviz_plugins/navsat
341+
name: INS Location
342+
config:
343+
visible: true
344+
collapsed: true
345+
topic: /gps/fix
346+
color: "#fce94f"
347+
draw_style: points
348+
position_tolerance: 0.5
349+
buffer_size: 0
350+
show_covariance: true
351+
show_all_covariances: false
352+
```

0 commit comments

Comments
 (0)