ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You are defining the parameters in different namespaces. Try defining the obstacle_sources under each costmap, i.e.:
obstacle_range: 2.5
raytrace_range: 3.0
max_obstacle_height: 2.0
footprint: [[0.285, 0.6365], [0.285, -0.6365], [-0.285, -0.6365], [-0.285, 0.6365]]
inflation_radius: 0.3
global_costmap/observation_sources: laser_scan_sensor point_cloud_sensor
local_costmap/observation_sources: laser_scan_sensor point_cloud_sensor
laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
point_cloud_sensor: {sensor_frame: camera_frame, data_type: PointCloud, topic: /camera/depth/points, marking: true, clearing: true}
planner_patience: 5.0
shutdown_costmaps: false
TrajectoryPlannerROS:
max_vel_x: 0.45
min_vel_x: 0.1
max_rotational_vel: 1.0
min_in_place_rotational_vel: 0.4
acc_lim_th: 2.0
acc_lim_x: 2.0
acc_lim_y: 2.0
sim_time: 1.0
pdist_scale: 0.6
gdist_scale: 0.8
occdist_scale: 0.01
holonomic_robot: true
global_costmap:
global_frame: map
robot_base_frame: base_footprint
update_frequency: 5.0
publish_frequency: 2.0
static_map: true
local_costmap:
global_frame: odom
robot_base_frame: base_footprint
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 3.0
height: 3.0
resolution: 0.01
2 | No.2 Revision |
You are defining the parameters in different namespaces. Try defining the obstacle_sources under each costmap, i.e.:
obstacle_range: 2.5
raytrace_range: 3.0
max_obstacle_height: 2.0
footprint: [[0.285, 0.6365], [0.285, -0.6365], [-0.285, -0.6365], [-0.285, 0.6365]]
inflation_radius: 0.3
global_costmap/observation_sources: laser_scan_sensor point_cloud_sensor
local_costmap/observation_sources: laser_scan_sensor point_cloud_sensor
laser_scan_sensor: global_costmap/laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
point_cloud_sensor: global_costmap/point_cloud_sensor: {sensor_frame: camera_frame, data_type: PointCloud, topic: /camera/depth/points, marking: true, clearing: true}
local_costmap/laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
local_costmap/point_cloud_sensor: {sensor_frame: camera_frame, data_type: PointCloud, topic: /camera/depth/points, marking: true, clearing: true}
planner_patience: 5.0
shutdown_costmaps: false
TrajectoryPlannerROS:
max_vel_x: 0.45
min_vel_x: 0.1
max_rotational_vel: 1.0
min_in_place_rotational_vel: 0.4
acc_lim_th: 2.0
acc_lim_x: 2.0
acc_lim_y: 2.0
sim_time: 1.0
pdist_scale: 0.6
gdist_scale: 0.8
occdist_scale: 0.01
holonomic_robot: true
global_costmap:
global_frame: map
robot_base_frame: base_footprint
update_frequency: 5.0
publish_frequency: 2.0
static_map: true
local_costmap:
global_frame: odom
robot_base_frame: base_footprint
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
rolling_window: true
width: 3.0
height: 3.0
resolution: 0.01
Source: http://wiki.ros.org/costmap_2d/hydro/obstacles#VoxelCostmapPlugin
I assumed that you want marking and clearing in both costmaps (which I do not think it is a common setup).