0
$\begingroup$

I am using Ubuntu 22.04, ROS2 - Humble version.Installed all packages using package manager.

I am building simulation for my robot and I noticed very strange behavior for global costmap. My robot has 180 degrees lidar in front of it. And the problem is, that after starting Nav2 system in simulation, global costmap updates only area, which is unseen previously.

For-example, if robot has obstacle in front of it, it will not be included in global costmap at the beginning. I must turn robot away from obstacle and then back, only then it will be updates by global costmap. Here is my config file for global planner:

vikings_bot_1/global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: map
      map_topic: /map
      #transform_tolerance: 0.5
      robot_base_frame: vikings_bot_1/base_link
      use_sim_time: True
      #robot_radius: 0.175
      footprint: "[[0.8, 0.45], [-0.3, 0.45], [-0.3, -0.45], [0.8, -0.45]]"
      resolution: 0.05
      track_unknown_space: true
      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /vikings_bot_1/lidar_scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 5.0
          raytrace_min_range: 0.0
          obstacle_max_range: 4.5
          obstacle_min_range: 0.0
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 4.0
        inflation_radius: 0.65
      always_send_full_costmap: True

Note: local costmap is updated correctly.

Here is video for the problem, as it might be hard to understand from description.

Any idea, where can be problem? I tried different planners as well, check parameters in config file..., but I could not find the cause of it.

$\endgroup$

1 Answer 1

0
$\begingroup$

That is very strange. Try turning off the static layer - are any laser scans working initially? Its not clear from your example that they are given that the other laser scans align with the map so that's already being inflated from the static layer. Any errors in the terminals? Perhaps the laser scans aren't actually making it into the costmap layers initially

$\endgroup$
4
  • $\begingroup$ I turned off static layer and updated *giff in original question. Yes, there is no update for global costmap initially although laser scan topic is working. Driving the robot clears costmap under the footprint as expected. But the problem still exist, that global costmap is updated only when turning the robot. There is no error in terminal launching path planner system. $\endgroup$
    – Hercogs
    Commented Dec 5, 2023 at 10:32
  • $\begingroup$ I found the reason behind this. The problem was, that lidar_link in map frame was in negative z direction. So, by increasing lidar hight (z offset) problem disappeared. $\endgroup$
    – Hercogs
    Commented Dec 5, 2023 at 11:44
  • $\begingroup$ Ah ok, I was about to say, that is so very strange, I have to think it was user error :-) $\endgroup$ Commented Dec 5, 2023 at 22:47
  • $\begingroup$ Can you click this answer as correct since its been debugged with the solution? $\endgroup$ Commented Dec 5, 2023 at 22:48

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.