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

How to configure Nav2 for a non-circular robot?

asked 2020-11-19 07:01:03 -0600

NEngelhard gravatar image

I am currently working with a rather rectangular AGV and would like to use Nav2 in ROS2/Foxy to drive it around safely. I started in simulation with the turtle-bot world and adapted mainly the footprint-parameter to describe the robot. I can load the simulation and the footprint is visualized, however the AGV ignores it when turning.

image description

Video of the whole sequence: robot starts from below, drives between the two obstacles, is the ordered to turn left and by doing so, moves its tail straight through an obstacle. (the simulated robot is small so that there is no collision detected) https://vimeo.com/user127468110/revie...

These are my costmap parameters:

I only replaced the robot_radius with the footprint, but this seems not to be enough to use the footprint. (Or am I missing something completely different?)

local_costmap:
  local_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 2.0
      global_frame: odom
      robot_base_frame: base_footprint
      use_sim_time: True
      rolling_window: true
      width: 5
      height: 5
      resolution: 0.02
      footprint: '[ [0.35, 0.35], [-0.7, 0.35], [-0.7, -0.35], [0.35, -0.35] ]'
      plugins: ["voxel_layer", "inflation_layer"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
      voxel_layer:
        plugin: "nav2_costmap_2d::VoxelLayer"
        enabled: True
        publish_voxel_map: True
        origin_z: 0.0
        z_resolution: 0.05
        z_voxels: 16
        max_obstacle_height: 2.0
        mark_threshold: 0
        observation_sources: scan
        scan:
          topic: /safety_scanner_left
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      static_layer:
        map_subscribe_transient_local: True
      always_send_full_costmap: True

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: map
      robot_base_frame: base_footprint
      use_sim_time: True
      footprint: '[ [0.35, 0.35], [-0.7, 0.35], [-0.7, -0.35], [0.35, -0.35] ]'
      resolution: 0.02
      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        footprint_clearing_enabled: False
        scan:
          topic: /safety_scanner_left
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
      always_send_full_costmap: True
edit retag flag offensive close merge delete

Comments

I'm not sure this is the issue but you should try to add the ObstacleLayer plugin to the local costmap

Alrevan gravatar image Alrevan  ( 2020-11-23 06:52:51 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2020-12-01 08:20:20 -0600

Alrevan gravatar image

updated 2020-12-01 08:22:30 -0600

Hello,

I had to dig a bit into this myself as the issue also appeared for my robot. I will assume you are using default nav2 setup.

It seems the issue is not coming from costmap parameters but from critics selection for dwb_controller. In fact, in the default parameters you have the following critics selected:

critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]

However if you look at the "default_critics.xml" file in the dwb_critics package you can find the following documentation about critics:

    <class type="dwb_critics::BaseObstacleCritic" base_class_type="dwb_core::TrajectoryCritic">
  <description>Uses costmap 2d to assign negative costs if a circular robot
               would collide at any point of the trajectory.
  </description>
</class>
<class type="dwb_critics::ObstacleFootprintCritic" base_class_type="dwb_core::TrajectoryCritic">
  <description>Uses costmap 2d to assign negative costs if robot footprint is in obstacle
               on any point of the trajectory.
  </description>

So for a rectangular robot you have to use the ObstacleFootprintCritic rather than the BaseObsctacleCritic.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-11-19 07:01:03 -0600

Seen: 992 times

Last updated: Dec 01 '20