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

Adding range_sensor_layer to layered costmap for global planning

asked 2015-04-07 16:02:43 -0500

Naman gravatar image

updated 2015-04-14 06:54:41 -0500

Hi all,

I am working on mobile robot navigation with the Hokuyo and Ultrasonic sensors. Hokuyo will be the main sensor for navigation and Ultrasound sensors will be used to detect obstacles not seen by the hokuyo (like Overhangs, etc). I already have the map of the environment. I have Rotational encoders to get the odometry information and IMU/UWB for localization.
I have added a range_sensor_layer ( http://wiki.ros.org/range_sensor_layer ) for the ultrasound sensor to the costmap (local and global). I am using the move_base ( http://wiki.ros.org/move_base ) package for navigation. The problem is that global planner still gives a path which passes through the obstacles detected by the ultrasound sensor and only the local planner takes care of avoiding that obstacle. The global planner takes care of the objects detected by the Hokuyo sensor and plans the path accordingly but ignores the obstacles detected by the ultrasound sensor while global planning. So, I want to ask how can I correctly include range_sensor_layer in the global costmap so that the global path does not give a path through the obstacles detected by the ultrasound sensor?

The relevant parameters are shown:

local_costmap_params.yaml

plugins:
  - {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
  - {name: sonar_layer,   type: "range_sensor_layer::RangeSensorLayer"}
  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}

  #Configuration for the sensors that the costmap will use to update a map   
  obstacle_layer:
    observation_sources: base_scan
    base_scan: {data_type: LaserScan, sensor_frame: /base_laser_link, topic: /base_scan, expected_update_rate: 0.4,
      observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}

  sonar_layer:
    topics: ["/sonar"]
    no_readings_timeout: 1.0

global_costmap_params.yaml

plugins:
  - {name: static_layer, type: "costmap_2d::StaticLayer"}
  - {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
  - {name: sonar_layer,   type: "range_sensor_layer::RangeSensorLayer"}

  #Configuration for the sensors that the costmap will use to update a map
  obstacle_layer:
    observation_sources: base_scan
    base_scan: {data_type: LaserScan, sensor_frame: /base_laser_link, topic: /base_scan, expected_update_rate: 0.4,
      observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}

  sonar_layer:
    topics: ["/sonar"]
    no_readings_timeout: 1.0

Update 1:
Gazebo simulation
image description

Global costmap Rviz Visualization
image description

As you can see, costmap visualization of the sonar obstacles in RViz does not look correct. The entire region in front of the sonar should be an obstacle which is not happening.

Update 2 (@Humpelstilzchen): I have pasted rostopic echo of single sonar message: image description

Update 3: The local costmap visualization of the sonar obstacles looks correct. Its only the global costmap which is wrong.

Local costmap Rviz visualization image description

It looks like I am missing out on something obvious but I am not able to figure it out. Does anyone have any idea about it?

Thanks in advance.
Naman Kumar

edit retag flag offensive close merge delete

Comments

1

When you visualize the costmap, does it reflect what you expect, with the sonar obstacles?

David Lu gravatar image David Lu  ( 2015-04-08 13:54:05 -0500 )edit
1

Hey @David, Costmap visualization makes sense with Hokuyo obstacles but with sonar obstacles, it is not what I expect. I have updated the original question with images showing gazebo simulation and rviz visualization. Costmap visualization of the sonar obstacles does not seem to be correct.

Naman gravatar image Naman  ( 2015-04-08 14:55:53 -0500 )edit

Is it just a single ranger on the front? Are there multiple readings sent?

David Lu gravatar image David Lu  ( 2015-04-08 17:47:20 -0500 )edit

@David, yes it is just a single ranger on the front. Gazebo is continuously publishing the sensor_msgs/Range message and the published Range message looks correct.

Naman gravatar image Naman  ( 2015-04-08 18:20:30 -0500 )edit

@Naman did you succeeded in mapping the environment using sonar sensor?

Kishore Kumar gravatar image Kishore Kumar  ( 2017-03-07 15:52:25 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2015-04-14 02:30:24 -0500

Humpelstilzchen gravatar image

updated 2015-04-14 12:22:04 -0500

(Actually only wanted to comment, but that always disappears..)

Did you check your configuration with rosparam? It is not clear for me from your paste, because in local_costmap_params.yaml the sonar_layer is in the obstacle_layer namespace, in global_costmap_params.yaml it is not


move the sonar_layer before the inflation layer.

edit flag offensive delete link more

Comments

1

Yep..that was the problem, Thanks a lot!

Naman gravatar image Naman  ( 2015-04-17 09:29:16 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2015-04-07 16:02:43 -0500

Seen: 5,233 times

Last updated: Apr 14 '15