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

local costmap stays empty / move_base not subscribing to laser

asked 2019-07-10 04:33:43 -0500

goeldisandro gravatar image

updated 2019-07-10 07:38:19 -0500

Hey there

A few weeks ago i finally brought the navigation on my Kobuki with an IMU (Beaglebone Blue), RPLidar and UP Squared as processing Unit up running. The localization came from google Cartographer. The drive commands came from move_base. Back then the local costmap as well as the global costmap contained the obstacles. This week i tried to tune the local and global planner for a smoother driving experience. Since i wanted to test it before tuning the local costmap stays empty. The navigation still works, but due to the lack of the local costmap the robot drives just straight to its goal. I think the problem is, that the move_base node does not subscribe to the scan topic. But i do not figure out how to force him to do so. I also tried to launch some backups, but the behaviour is the same.

my TF_tree is:

  • map (map-odom = global SLAM)
  • odom (odom-base_footprint = local SLAM)
  • base_footprint (base_footprint - base_link = (0, 0, 0, 1) quaterninon with own tf broadcaster)
  • base_link (base_link - scan/imu_link = direction on robot with urdf)
  • scan / imu_link

The Cartographer is still working well and provides the Transformation as far as i can see. The topic /scan and /imu are both published and seem right. A picture from the Navigation with the empty costamp is added here: navigation with empty costmap .

Does anyone has some ideas, which might bring my robot to update the local_costmap? The important files are added below and the others are in: https://github.com/goeldisandro/autonomous_turtlebot_navigation.

thanks a lot for your help!

greetings from Switzerland

Edit:

  1. the first failure is:
[ WARN] [1562752396.232648210]: Control loop missed its desired rate

of 20.0000Hz... the loop actually took 0.1233 seconds

am i right, that this is just a performance issue?

  1. there is also an Error that i do not really know, what does it mean
[ERROR] [1562757979.010348657]: Kobuki : malformed sub-payload

detected. [28][170][1C AA 55 4D 01 0F A4 18 00 00 ]

the Error also showed up before, which makes me think it is not important. I also found no way to fix it (already tried updating Kobuki).

this is the Output when i launch

>  NODES   /
>     bumper2pointcloud (nodelet/nodelet)
>     cartographer_node (cartographer_ros/cartographer_node)
>     cartographer_occupancy_grid_node (cartographer_ros/cartographer_occupancy_grid_node)
>     cmd_vel_mux (nodelet/nodelet)
>     diagnostic_aggregator (diagnostic_aggregator/aggregator_node)
>     mobile_base (nodelet/nodelet)
>     mobile_base_nodelet_manager (nodelet/nodelet)
>     move_base (move_base/move_base)
>     robot_state_publisher (robot_state_publisher/robot_state_publisher)
>     rplidarNode (rplidar_ros/rplidarNode)
>     rviz (rviz/rviz)
>     tf_broadcaster_base (robot_setup_tf/tf_broadcaster_base)
> 
> ROS_MASTER_URI=http://localhost:11311
> 
> process[rplidarNode-1]: started with
> pid [18294] [ INFO]
> [1562752257.374873089]: RPLIDAR
> running on ROS package rplidar_ros.
> SDK Version:1.9.0 process[rviz-2]:
> started with pid [18317]
> process[tf_broadcaster_base-3]:
> started with pid [18318]
> process[robot_state_publisher-4]:
> started with pid [18319]
> process[diagnostic_aggregator-5]:
> started with pid [18328]
> process[mobile_base_nodelet_manager-6]:
> started with pid [18337]
> process[mobile_base-7]: started with
> pid [18349]
> process[bumper2pointcloud-8]: started
> with pid [18359 ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2019-07-11 02:45:48 -0500

pavel92 gravatar image

updated 2019-07-11 03:17:51 -0500

Regarding the Control loop missed its desired rate warning check out this answer. You might need to reduce the controller_frequency parameter in move_base.launch. Also check if the scanner is actually publishing LaserScan messages on the /scan topic.
In addition, what do you think by local costmap stays empty"? No new obstacles can be seen in the local costmap but the ones from the map are seen on the static global costmap? In move_base case the global planner plans a path around the obstacles detected in global_costmap and and local planner tries to avoid obstacles on the path detected in local_costmap.

I checked you costmap_common_params.yaml file and I see that you have commented out some sensor parameters in the obstacle_layer. Try setting it like this and recheck if the frame/topics are correct:

  obstacle_layer:
    observation_sources: laser_scan_sensor
    laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true, min_obstacle_height: 0.0, max_obstacle_height: 5.0, obstacle_range: 6.0, raytrace_range: 8.5}

Also no point in having the global_frame and robot_base_frame in costmap_common_params.yaml if you are reinitializing them in the local and global costmap params files. Plus be careful with any namespaces and "/" in the names.

I would put the plugins before the layer description in costmap_common_params.yaml:

  plugins:
    - {name: inflation_layer,        type: "costmap_2d::InflationLayer"}
    - {name: obstacle_layer,         type: "costmap_2d::ObstacleLayer"}

and move the static_layer into your global_costmap params file

  static_layer:
    map_topic: /map
    subscribe_to_updates: true
    static_map: true

For example you can always checkout the jackal_navgation package which gives a good example on the configuration files

edit flag offensive delete link more

Comments

I will try your suggestions on monday and tell you the results asap.

As far as i can see the /scan topic is published right. I can also visualize the scan in rviz and it seems right. The only point is that the points, that are to close to the sensor get an undefined value.

I think i understand the concept with local/global planer/costmap. In a previous version of mine the obstacles first were added to the local costmap and later to the global costmap. This enabled the local as well as the global planer to find a good way. With the empty local costmap the planer just drives straight to its goal, no matter if there are some scanned obstacles on the route.

Thanks a lot for your help.

goeldisandro gravatar image goeldisandro  ( 2019-07-11 11:45:17 -0500 )edit
0

answered 2019-07-15 07:37:58 -0500

goeldisandro gravatar image

I finally found my failures. the first failure was that i loaded the costmap_common_files without namespace (ns)

<!-- move base node  ########################################################################## -->

  <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS"/>
    <param name="base_global_planner" value="carrot_planner/CarrotPlanner"/>
  <param name="robot_description"
    textfile="$(find cartographer_ros)/urdf/00_Kobuki_rp.urdf" />

   <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
   <rosparam file="$(find kobuki_nav)/costmap_common_params.yaml" command="load" ns="global_costmap" /> 
   <rosparam file="$(find kobuki_nav)/costmap_common_params.yaml" command="load" ns="local_costmap" />

   <rosparam file = "$(find kobuki_nav)/local_costmap_params.yaml" command="load" />
   <rosparam file="$(find kobuki_nav)/global_costmap_params.yaml" command="load" />    

   <rosparam file="$(find kobuki_nav)/dwa_local_planner_params.yaml" command="load" /> 
   <rosparam file="$(find kobuki_nav)/base_local_planner_params.yaml" command="load" /> 
   </node>

And the second thing is that the *_params.yaml needed a little adaption

the right settings are below:

costmap_common_parameters.yaml

  map_type: costmap
  origin_z: 0.0
  z_resolution: 1
  z_voxels: 2

  obstacle_range: 2.5
  raytrace_range: 3.0

  publish_voxel_map: true
  transform_tolerance: 0.5
  meter_scoring: true

  footprint: [[-0.21, -0.165], [-0.21, 0.165], [0.21, 0.165], [0.21, -0.165]]
  footprint_padding: 0.1

  plugins:
    - {name: static_layer, type: "costmap_2d::StaticLayer"}
    - {name: obstacles_layer, type: "costmap_2d::VoxelLayer"}
    - {name: inflater_layer, type: "costmap_2d::InflationLayer"}

  static_layer:
    map_topic: /map
    subscribe_to_updates: true
    static_map: true  

  obstacles_layer:
    observation_sources: scan
    scan: {sensor_frame: rp_link, data_type: LaserScan, topic: scan, marking: true, clearing: true, min_obstacle_height: -2.0, max_obstacle_height: 2.0, obstacle_range: 2.5, raytrace_range: 8.5}

  inflater_layer:
    inflation_radius: 0.1

local_costmap_parameters.yaml

local_costmap:
   global_frame: map
   robot_base_frame: base_footprint
   update_frequency: 20.0
   publish_frequency: 5.0
   width: 10.0
   height: 10.0
   resolution: 0.05
   static_map: false
   rolling_window: true

global_costmap_parameters.yaml

global_costmap:
   global_frame: map
   robot_base_frame: base_footprint
   update_frequency: 20.0
   publish_frequency: 5.0
   width: 40.0
   height: 40.0
   resolution: 0.05
   origin_x: -20.0
   origin_y: -20.0
   static_map: true
   rolling_window: false
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-07-10 04:33:43 -0500

Seen: 1,758 times

Last updated: Jul 15 '19