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