ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Robot and sensor are out of map bounds (Local Costmap- Voxel Layer)

asked 2023-05-04 17:57:48 -0500

Vini71 gravatar image

updated 2023-05-04 18:02:28 -0500

Hi I am at this step footprint step of tutorial of NAV2. However I am configuring for my specific robot. Given that I have different dimensions, range for lidar and map size, I have configured different values for mapping (mapper_params_online_async.yaml) and for the costmaps (nav2_params.yaml)

1 - I launch my display.launch file, Rviz and Gazebo is opened properly with the lidar set correctly (at least in terms of Transform and subscribing /scan messages)

2- Secondly I launch the online_async_launch.py launch file and get no errors:

INFO] [launch]: All log files can be found below /home/rota/.ros/log/2023-05-04-19-40-07-815644-NUC-21912
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [async_slam_toolbox_node-1]: process started with pid [21914]
[async_slam_toolbox_node-1] [INFO] [1683240007.920155126] [slam_toolbox]: Node using stack size 40000000
[async_slam_toolbox_node-1] [INFO] [1683240008.344782676] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[async_slam_toolbox_node-1] [INFO] [1683240008.345652180] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.    INFO] [launch]: All log files can be found below /home/rota/.ros/log/2023-05-04-19-40-07-815644-NUC-21912
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [async_slam_toolbox_node-1]: process started with pid [21914]
[async_slam_toolbox_node-1] [INFO] [1683240007.920155126] [slam_toolbox]: Node using stack size 40000000
[async_slam_toolbox_node-1] [INFO] [1683240008.344782676] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[async_slam_toolbox_node-1] [INFO] [1683240008.345652180] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[async_slam_toolbox_node-1] Registering sensor: [Custom Described Lidar]


[async_slam_toolbox_node-1] Registering sensor: [Custom Described Lidar]

3- I launched the navigation_launch.py . Unfortunately in this step the error is raised:

**[planner_server-2] [WARN] [1683239305.550661960] [nav2_costmap_2d]: Robot is out of bounds of the costmap! I checked that this error raises from the costmap voxel plugin function (rows 318-328) : voxel_layer.cpp

I have already changed the following parameters:

  • Map size
  • Laser Range (from 15 to 100)
  • Global and Local Costmap values (resolution, width, height, origin_x, origin_y, maximum height, etc)

I wonder if this costmap error is raised because my lidar is pitched to the ground (Lidar Orientation, Position), so the range in x direction is smaller than at y direction, or is it my Lidar in a too high spot ? over truck's cabin...

Gazebo image description

Rviz2

image description

As you can check the global costmap is drawed properly and its footprint as well

However the local costmap is not generated and its respective footprint also not! In this way the path planner won't work well (at least the obstacle avoidance)...since I don't have the local costmap

What can be leading to this error?

Thanks in advance

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
0

answered 2023-05-05 17:11:16 -0500

Vini71 gravatar image

updated 2023-05-05 17:32:51 -0500

After an extensive investigation involving adjusting various parameters innav2_params.yaml and experimenting with different positions and orientations of the LiDAR sensor, I discovered that the issue was not related to the sensor's range, pose, FOV, or any other related factors.

The root of the problem lies in the configuration of theslam-toolbox package. For some reason, it was misconfigured and did not work properly with the local costmap and voxel layer.

When running a static transform publisher (map --> odom):

ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0 map odom

Both local and global costmaps are generated, but the map itself is not produced:

image description

image description

Adjustments were made to the Voxel map range (width, height), and the raytrace range was increased to better suit the robot's dimensions and the environment's size.

However, when running the slam dynamic transform (map --> odom) using :

ros2 launch slam_toolbox online_sync_launch.py

The map and global costmap are generated, but the local costmap is not (even for the TurtleBot3 Waffle tutorial example or for my robot):

image description

A closer examination of the /tf topic reveals differences between the transforms when using the slam-toolbox async node and the static transform.

  1. slam-toolbox async node:

    transforms:

    • header: stamp: sec: 47 nanosec: 381000000 frame_id: map child_frame_id: odom transform: translation: x: 3.4662790218048424e-06 y: -2.2171464780663484e-07 z: -0.400019324960254 rotation: x: -2.7712992106286824e-07 y: -4.332639404341957e-06 z: 1.1986118037611005e-12 w: 0.9999999999905756
  2. static transform:


    transforms:

    • header: stamp: sec: 33 nanosec: 92000000 frame_id: odom child_frame_id: base_link transform: translation: x: -0.02042282951343617 y: -0.014272684253787292 z: 0.8999813856701359 rotation: x: 3.8079219550742497e-08 y: 3.443628320324917e-06 z: -0.0021973022911122857 w: 0.9999975859224768

When using the static transform, there is no periodic transform published between the map and odom frames. I suspect that the local costmap plugin might rely on this transform (although I'm not certain), and when using the slam mapping node, the periodic transform between the odom and map frames may interfere or overlap with the static transform, potentially causing conflicts.

It's unclear how the Voxel grid plugin code is integrated with the slam-toolbox and how it affects the local costmap generation. Further investigation into the interplay between these components is needed to pinpoint the exact cause of the issue.

In summary, the problem seems to stem from the slam-toolbox configuration and its interaction with the local costmap and voxel layer. A thorough investigation of the relevant components and their interdependencies could potentially reveal the root cause and offer a more permanent solution.

edit flag offensive delete link more
0

answered 2023-07-27 14:21:23 -0500

dcconner gravatar image

Answer cross posted at #384944

I saw this issue with a fake localization and map server with Nav2. I traced the issue to "latched" topics. If I start map server after nav2 nodes, then it works.

Per https://docs.ros.org/en/rolling/Conce... A map_server publishing as "transient_local" should be readable by subscriber as volatile, but this doesn't seem to work in humble.

See discussion at https://github.com/ros2/ros2/issues/464

To see old messages, the subscriber also needs to be "transient local". Nav2 costmap subscribes as "volatile" (at least in humble), so it does not see the old map.

edit flag offensive delete link more

Comments

check ros2 param get /global_costmap/global_costmap static_layer.map_subscribe_transient_local

dcconner gravatar image dcconner  ( 2023-07-27 15:14:03 -0500 )edit
0

answered 2023-05-05 12:35:27 -0500

updated 2023-05-05 12:36:05 -0500

I think its actually pretty clear, your map's edges are looking like they intersect with the front bumper of your vehicle (more or less, the exactness isn't the point). Your vehicle's fixed frame used for planning is presumably somewhere in the center of the cab or the articulation point or similar. That is literally off the map in the most actual meaning. To plan in the map, you need the robot to be in the map itself, so meaning either you need to pre-map the space, teleop the first bits so you can get context about the space around it, or add more sensors so your system has information about whats around it.

You're kind of asking for the impossible if you don't have sensor coverage on the sides / back and you ask the robot to navigate somewhere far away where it both (1) has no map to know where things are or (2) has no sensors to decide what's there right now. How could it know anything else?

edit flag offensive delete link more

Comments

Hi Steve, I appreciate your insights on this issue. I have a related question regarding the configuration of the robot_model_type parameter in the slam/AMCL package for Ackermann steering. According to the AMCL configuration documentation, the default motion models are "differential" or "omni."

Considering that the SMAC planner configuration documentation mentions that NAV2 supports Ackermann kinematics, I'm curious if there is already an available plugin for Ackermann steering that can be used as a parameter in the nav2_params.yaml file. Alternatively, could using the "differential" model provide a similar effect or at least a functional solution for Ackermann-steered robots?

Vini71 gravatar image Vini71  ( 2023-05-05 17:25:13 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2023-05-04 17:57:48 -0500

Seen: 889 times

Last updated: Jul 27 '23