|
| 1 | +.. _gridmap_outdoor_navigation: |
| 2 | + |
| 3 | +========================================= |
| 4 | +Outdoor Navigation with GridMaps (Summit) |
| 5 | +========================================= |
| 6 | + |
| 7 | +This HowTo demonstrates how to run **EasyNav** outdoors using **GridMap** representation and the **Summit robot**. |
| 8 | +It uses the *GridMap Maps Manager* for environment representation and the *LidarSLAM Localizer plugin* for real-time localization. |
| 9 | + |
| 10 | +.. contents:: On this page |
| 11 | + :local: |
| 12 | + :depth: 2 |
| 13 | + |
| 14 | +Overview |
| 15 | +-------- |
| 16 | + |
| 17 | +.. raw:: html |
| 18 | + |
| 19 | + <div align="center"> |
| 20 | + <iframe width="450" height="300" src="https://www.youtube.com/embed/mxivTYNY1yY" frameborder="0" allowfullscreen></iframe> |
| 21 | + </div> |
| 22 | + |
| 23 | +In this tutorial, you will: |
| 24 | + |
| 25 | +1. Launch the **Summit** outdoor simulator. |
| 26 | +2. Start the **EasyNav** system configured for GridMap-based navigation. |
| 27 | +3. Use **RViz2** to send navigation goals interactively. |
| 28 | + |
| 29 | +This example combines the **GridMap** framework (for multi-layer terrain representation) and **LidarSLAM** (for localization from point clouds). |
| 30 | +It showcases how EasyNav seamlessly integrates mapping, localization, planning, and control in outdoor environments. |
| 31 | + |
| 32 | +--- |
| 33 | + |
| 34 | +Setup |
| 35 | +----- |
| 36 | + |
| 37 | +1. You have completed the installation described in :doc:`../build_install/index`. |
| 38 | +2. You have a working workspace containing the following repositories: |
| 39 | + |
| 40 | + - ``EasyNavigation`` |
| 41 | + - ``easynav_plugins`` |
| 42 | + - ``easynav_gridmap_stack`` *(for GridMap representation and planner)* |
| 43 | + - ``easynav_lidarslam_ros2`` *(for SLAM)* |
| 44 | + - ``easynav_playground_summit`` *(for the Summit simulation world)* |
| 45 | + |
| 46 | +If something is missing, clone the required repositories: |
| 47 | + |
| 48 | +.. code-block:: bash |
| 49 | +
|
| 50 | + cd ~/ros/ros2/easynav_ws/src |
| 51 | + git clone https://github.com/EasyNavigation/easynav_plugins.git |
| 52 | + git clone https://github.com/EasyNavigation/easynav_playground_summit.git |
| 53 | + git clone https://github.com/EasyNavigation/easynav_outdoor_testcase.git |
| 54 | + git clone -b rolling https://github.com/EasyNavigation/easynav_lidarslam_ros2.git |
| 55 | + git clone -b rolling_ament_fixed https://github.com/fmrico/grid_map.git |
| 56 | +
|
| 57 | +.. warning:: |
| 58 | + |
| 59 | + The official `grid_map` repository still uses ``ament_target_dependencies()``, |
| 60 | + which is deprecated in recent ROS 2 distributions. |
| 61 | + Use the patched fork above (branch ``rolling_ament_fixed``) to ensure successful builds. |
| 62 | + |
| 63 | +Then build and source your workspace: |
| 64 | + |
| 65 | +.. code-block:: bash |
| 66 | +
|
| 67 | + cd ~/ros/ros2/easynav_ws |
| 68 | + rosdep install --from-paths src --ignore-src -r -y |
| 69 | + colcon build --symlink-install |
| 70 | + source install/setup.bash |
| 71 | +
|
| 72 | +--- |
| 73 | + |
| 74 | +1. Launch the Simulator |
| 75 | +----------------------- |
| 76 | + |
| 77 | +Start the **Summit** world simulation. |
| 78 | +This environment includes outdoor terrain suitable for GridMap-based navigation. |
| 79 | + |
| 80 | +.. code-block:: bash |
| 81 | +
|
| 82 | + ros2 launch easynav_playground_summit playground_summit.launch.py |
| 83 | +
|
| 84 | +Keep the RViz window open to visualize sensor topics and the simulated environment. |
| 85 | + |
| 86 | +--- |
| 87 | + |
| 88 | +2. Launch EasyNav with GridMap and LidarSLAM |
| 89 | +-------------------------------------------- |
| 90 | + |
| 91 | +Next, launch **EasyNav** with the following parameter file configuration. |
| 92 | + |
| 93 | +Save the following YAML file as |
| 94 | +``~/ros/ros2/easynav_ws/src/easynav_outdoor_testcase/robots_params/gridmap.lidarslam.params.yaml`` |
| 95 | + |
| 96 | +.. code-block:: yaml |
| 97 | +
|
| 98 | + controller_node: |
| 99 | + ros__parameters: |
| 100 | + use_sim_time: true |
| 101 | + controller_types: [simple] |
| 102 | + simple: |
| 103 | + rt_freq: 30.0 |
| 104 | + plugin: easynav_simple_controller/SimpleController |
| 105 | + max_linear_speed: 1.0 |
| 106 | + max_angular_speed: 1.0 |
| 107 | + look_ahead_dist: 0.2 |
| 108 | + k_rot: 0.5 |
| 109 | +
|
| 110 | + localizer_node: |
| 111 | + ros__parameters: |
| 112 | + use_sim_time: true |
| 113 | + localizer_types: [lidarslam] |
| 114 | + lidarslam: |
| 115 | + plugin: easynav_lidarslam_localizer/LidarSlamLocalizer |
| 116 | + input_cloud: /front_laser/points |
| 117 | + imu: /imu/data |
| 118 | +
|
| 119 | + maps_manager_node: |
| 120 | + ros__parameters: |
| 121 | + use_sim_time: true |
| 122 | + map_types: [gridmap] |
| 123 | + gridmap: |
| 124 | + freq: 10.0 |
| 125 | + plugin: easynav_gridmap_maps_manager/GridmapMapsManager |
| 126 | + package: easynav_outdoor_testcase |
| 127 | + map_path_file: maps/pool.yaml |
| 128 | +
|
| 129 | + planner_node: |
| 130 | + ros__parameters: |
| 131 | + use_sim_time: true |
| 132 | + planner_types: [astar] |
| 133 | + astar: |
| 134 | + plugin: easynav_gridmap_astar_planner/GridMapAStarPlanner |
| 135 | + max_allowed_slope_deg: 20.0 |
| 136 | +
|
| 137 | + sensors_node: |
| 138 | + ros__parameters: |
| 139 | + use_sim_time: true |
| 140 | + forget_time: 0.5 |
| 141 | + sensors: [laser1] |
| 142 | + perception_default_frame: odom |
| 143 | + laser1: |
| 144 | + topic: /front_laser_sensor/points |
| 145 | + type: sensor_msgs/msg/PointCloud2 |
| 146 | + group: points |
| 147 | +
|
| 148 | + system_node: |
| 149 | + ros__parameters: |
| 150 | + use_sim_time: true |
| 151 | + position_tolerance: 0.1 |
| 152 | + angle_tolerance: 0.05 |
| 153 | +
|
| 154 | + # LidarSLAM parameters (used internally by the localizer plugin) |
| 155 | + scan_matcher: |
| 156 | + ros__parameters: |
| 157 | + use_sim_time: True |
| 158 | + global_frame_id: "map" |
| 159 | + robot_frame_id: "base_link" |
| 160 | + odom_frame_id: "odom" |
| 161 | + registration_method: "NDT" |
| 162 | + ndt_resolution: 2.0 |
| 163 | + ndt_num_threads: 2 |
| 164 | + gicp_corr_dist_threshold: 5.0 |
| 165 | + trans_for_mapupdate: 1.5 |
| 166 | + vg_size_for_input: 0.5 |
| 167 | + vg_size_for_map: 0.2 |
| 168 | + use_min_max_filter: true |
| 169 | + scan_min_range: 1.0 |
| 170 | + scan_max_range: 200.0 |
| 171 | + scan_period: 0.2 |
| 172 | + map_publish_period: 15.0 |
| 173 | + num_targeted_cloud: 20 |
| 174 | + set_initial_pose: true |
| 175 | + initial_pose_x: 0.0 |
| 176 | + initial_pose_y: 0.0 |
| 177 | + initial_pose_z: 0.0 |
| 178 | + initial_pose_qx: 0.0 |
| 179 | + initial_pose_qy: 0.0 |
| 180 | + initial_pose_qz: 0.0 |
| 181 | + initial_pose_qw: 1.0 |
| 182 | + use_imu: false |
| 183 | + use_odom: false |
| 184 | + debug_flag: false |
| 185 | +
|
| 186 | + graph_based_slam: |
| 187 | + ros__parameters: |
| 188 | + use_sim_time: True |
| 189 | + registration_method: "NDT" |
| 190 | + ndt_resolution: 1.0 |
| 191 | + ndt_num_threads: 2 |
| 192 | + voxel_leaf_size: 0.2 |
| 193 | + loop_detection_period: 3000 |
| 194 | + threshold_loop_closure_score: 0.7 |
| 195 | + distance_loop_closure: 100.0 |
| 196 | + range_of_searching_loop_closure: 20.0 |
| 197 | + search_submap_num: 2 |
| 198 | + num_adjacent_pose_cnstraints: 5 |
| 199 | + use_save_map_in_loop: true |
| 200 | + debug_flag: true |
| 201 | +
|
| 202 | +.. note:: |
| 203 | + |
| 204 | + The **LidarSLAM parameters** (``scan_matcher`` and ``graph_based_slam``) are defined **after** the main EasyNav nodes. |
| 205 | + These settings are used internally by the ``easynav_lidarslam_localizer/LidarSlamLocalizer`` plugin, which encapsulates |
| 206 | + `lidarslam_ros2` for seamless integration into the EasyNav localization framework. |
| 207 | + |
| 208 | +Then, launch EasyNav with: |
| 209 | + |
| 210 | +.. code-block:: bash |
| 211 | +
|
| 212 | + ros2 run easynav_system system_main \ |
| 213 | + --ros-args --params-file ~/ros/ros2/easynav_ws/src/easynav_outdoor_testcase/robots_params/gridmap.lidarslam.params.yaml |
| 214 | +
|
| 215 | +You should now see console logs from the GridMap Maps Manager, the planner, and the LidarSLAM localizer starting up. |
| 216 | + |
| 217 | +--- |
| 218 | + |
| 219 | +3. Commanding Navigation Goals |
| 220 | +------------------------------ |
| 221 | + |
| 222 | +Once EasyNav is running, open **RViz2** (if not already open) and add the **2D Goal Pose** tool. |
| 223 | + |
| 224 | +.. code-block:: bash |
| 225 | +
|
| 226 | + ros2 run rviz2 rviz2 --ros-args -p use_sim_time:=true |
| 227 | +
|
| 228 | +Click anywhere in the map to send navigation goals to the system. |
| 229 | +The robot will compute paths using the **GridMap A\* Planner** and execute them via the **Simple Controller**. |
| 230 | + |
| 231 | +You can observe in RViz: |
| 232 | + |
| 233 | +- The **GridMap layers** published by the Maps Manager. |
| 234 | +- The **path** generated by the A\* planner. |
| 235 | +- The **robot trajectory** updated in real time as the LidarSLAM localizer refines the pose. |
| 236 | + |
| 237 | +--- |
| 238 | + |
| 239 | +Notes |
| 240 | +----- |
| 241 | + |
| 242 | +- This tutorial uses the **LidarSLAM Localizer plugin**, which wraps `lidarslam_ros2` internally for tighter integration with EasyNav. |
| 243 | +- GridMap enables **multi-layer outdoor representation**, supporting elevation, traversability, and slope data. |
| 244 | +- The **A\*** planner respects elevation limits using the parameter ``max_allowed_slope_deg``. |
| 245 | +- You can edit the YAML file under ``maps/pool.yaml`` to try different outdoor maps or terrains. |
| 246 | + |
| 247 | +--- |
| 248 | + |
| 249 | +With this setup, your Summit robot navigates outdoor environments using real-time LidarSLAM localization and GridMap-based path planning. |
| 250 | +It provides a complete example of **EasyNav’s 3D-aware navigation stack** in simulation. |
0 commit comments