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

Robot does not percieve other robots as obstacles

asked 2021-11-18 06:07:07 -0600

WarTurtle gravatar image

updated 2022-02-13 17:10:18 -0600

lucasw gravatar image

I have a multi robot system where they all have a version of the navstack with different namespaces. They all share the same costmap parameters but again in a different namespace.

The problem is that when I give a 2d nav goal to a robot, it moves somewhat biasedly in a straight line, and runs straight into another robot. There is plenty of space to navigate around it, but it seems it does not percieve it as an obstacle, even though it is visible that it shows up on the laserscan.

Please take a look at the linked video. https://imgur.com/a/6d81brc I apologize for the bad quality, I tried to use kazam, but it just recorded a black screen of rviz.


Here are the costmap and planner parameters:

Global costmap parameter:

global_costmap:
  global_frame: map
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5

  static_map: true

Local costmap parameter:

local_costmap:
  global_frame: odom
  robot_base_frame: base_footprint

  update_frequency: 10.0
  publish_frequency: 10.0
  transform_tolerance: 0.5  

  static_map: false  
  rolling_window: true
  width: 3
  height: 3
  resolution: 0.05

Costmap common parameter:

obstacle_range: 3.0
raytrace_range: 3.5

footprint: [[-0.105, -0.105], [-0.105, 0.105], [0.041, 0.105], [0.041, -0.105]]
#robot_radius: 0.105

inflation_radius: 1.75 #default 1.0
cost_scaling_factor: 20 #default 3.0

map_type: costmap
observation_sources: scan
scan: {sensor_frame: base_scan, data_type: LaserScan, topic: scan, marking: true, clearing: true}

Global planner parameter:

GlobalPlanner:                                  
  old_navfn_behavior: false                     
  use_quadratic: true                           
  use_dijkstra: true                            
  use_grid_path: false                          

  allow_unknown: true                           
  planner_window_x: 0.0                         # default 0.0
  planner_window_y: 0.0                         # default 0.0
  default_tolerance: 0.0                        

  publish_scale: 100                            
  planner_costmap_publish_frequency: 0.0        # default 0.0

  lethal_cost: 253                              # default 253
  neutral_cost: 50                              # default 50
  cost_factor: 3.0                              # default 3.0
  publish_potential: true

DWA local planner parameter:

DWAPlannerROS:

# Robot Configuration Parameters
  max_vel_x: 0.22
  min_vel_x: -0.22

  max_vel_y: 0.0
  min_vel_y: 0.0

# The velocity when robot is moving in a straight line
  max_vel_trans:  0.22
  min_vel_trans:  0.11

  max_vel_theta: 5.0 #Default 2.75
  min_vel_theta: 2.5 #default 1.37

  acc_lim_x: 2.5
  acc_lim_y: 0.0
  acc_lim_theta: 3.2 

# Goal Tolerance Parametes
  xy_goal_tolerance: 0.05
  yaw_goal_tolerance: 0.17
  latch_xy_goal_tolerance: false

# Forward Simulation Parameters
  sim_time: 4.5 #Default 1.5
  vx_samples: 20
  vy_samples: 0
  vth_samples: 40
  controller_frequency: 10.0

# Trajectory Scoring Parameters
  path_distance_bias: 32.0
  goal_distance_bias: 8.0 #Default 20.0
  occdist_scale: 0.00 #Default 0.02
  forward_point_distance: 0.0 #Default 0.325
  stop_time_buffer: 0.2
  scaling_speed: 0.25
  max_scaling_factor: 0.2

# Oscillation Prevention Parameters
  oscillation_reset_dist: 0.05

# Debugging
  publish_traj_pc : true
  publish_cost_grid_pc: true
edit retag flag offensive close merge delete

Comments

1

Are odom, base_footprint, and base_scan the same as in the current tf? I think it is possible that base_scan does not exist. It may work if you change sensor_frame: base_scan to sensor_frame: base_footprint.

miura gravatar image miura  ( 2021-11-18 08:53:18 -0600 )edit
1

It worked by adding a namespace before base_scan and scan:

scan: {sensor_frame: Bot1/base_scan, data_type: LaserScan, topic: Bot1/scan, marking: true, clearing: true}
WarTurtle gravatar image WarTurtle  ( 2021-11-24 06:36:55 -0600 )edit

@WarTurtle Congratulations on the resolution. You can create your own answer and make it resolved.

miura gravatar image miura  ( 2021-11-24 07:32:10 -0600 )edit
1

@miura Yes, I will do that when I figure out how to make it more general e.g.

scan: {sensor_frame: $(arg namespace)/base_scan, data_type: LaserScan, topic: $(arg namespace)/scan, marking: true, clearing: true}
WarTurtle gravatar image WarTurtle  ( 2021-11-25 02:58:29 -0600 )edit

3 Answers

Sort by ยป oldest newest most voted
2

answered 2021-12-09 07:27:15 -0600

WarTurtle gravatar image

Thank you, @fergs , @osilva , and @miura for your help. The problem was in costmap common parameter, specifically in

scan: {sensor_frame: base_scan, data_type: LaserScan, topic: scan, marking: true, clearing: true}

I could not work out to remap it from the launch file when it is inside the dictionary. The solution was to add n costmap_common_params.yaml files for n robots with names specific to the namespace of the robot, e.g. costmap_common_params_Bot1.yaml would contain

scan: {sensor_frame: Bot1/base_scan, data_type: LaserScan, topic: Bot1/scan, marking: true, clearing: true}

I could then call these in the launch file using:

<rosparam file="$(find deploy)/param/costmap_common_params_$(arg namespace).yaml"
command="load" ns="global_costmap" />

<rosparam file="$(find deploy)/param/costmap_common_params_$(arg namespace).yaml"
command="load" ns="local_costmap" />

Hope this can help anyone else having problems with this.

edit flag offensive delete link more
1

answered 2021-11-18 06:31:29 -0600

osilva gravatar image

updated 2021-11-18 06:33:15 -0600

Very cool video. Thank you for sharing all the pertinent information.

Here is a link of Navigation Guide, please read when you have a chance as it explains steps to solve navigation problems in the future: https://kaiyuzheng.me/documents/navgu...

From the video, it looks the obstacle is detected but the path generated is too close to the obstacle, so it ends up hitting the obstacle so I'd start by taking a look at your cost function.

The cost function used to score each trajectory is in the following form:

cost = path_distance_bias * (distance to path from the endpoint of the trajectory in meters) + goal_distance_bias * (distance to local goal from the endpoint of the trajectory in meters) + occdist_scale * (maximum obstacle cost along the trajectory in obstacle cost (0-254))

Source: http://wiki.ros.org/dwa_local_planner

In this case your occdist_scale is 0.00 so basically you are not adding weight to avoid obstacles.

edit flag offensive delete link more
0

answered 2021-11-18 08:03:34 -0600

fergs gravatar image

It is hard to tell for sure from the video - but it really looks like your laser scan is not actually being marked in the costmap - there should be a big blue circle around that other robot since it is showing up in the laser scan - but the blue inflation area seems to only follow the static map (there are also a pair of laser pixels on the very right of the screen, and they have no marking under them). I'm not sure which setting is wrong, but I would start by getting the costmap to properly include the laser scan data.

edit flag offensive delete link more

Comments

This is exactly what was wrong. The remapping in the launch files could not remap the dictionary in the costmap common parameter

Changing this manually to

scan: {sensor_frame: Bot1/base_scan, data_type: LaserScan, topic: Bot1/scan, marking: true, clearing: true}

where Bot1 is the namespace, it works flawlessly (Also increasing the occdist_scale as osilva mentioned)

WarTurtle gravatar image WarTurtle  ( 2021-11-24 06:39:44 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2021-11-18 06:07:07 -0600

Seen: 145 times

Last updated: Dec 09 '21