ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
In config/sensors_rgbd.yaml
(file specified in launch/<robot>_moveit_sensor_manager.launch
) replace
- sensor_type: point_cloud_sensor
with
- sensor_plugin: occupancy_map_monitor/PointCloudOctoapUpdater
Hint from MoveIt Google Group (sorry not enough karma to publish links...)
Here my working sensors_rgbd.yaml
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /kinect/depth_registered/points
max_range: 5.0
frame_subsample: 1
point_subsample: 1
self_mask:
min_sensor_dist: .8
self_see_default_padding: .04
self_see_default_scale: 1.0
self_see_links:
- name: katana_internal_controlbox_link
- name: katana_base_link
- name: katana_motor1_pan_link
- name: katana_motor2_lift_link
padding: 0.06
- name: katana_motor3_lift_link
padding: 0.06
- name: katana_motor4_lift_link
padding: 0.06
- name: katana_motor5_wrist_roll_link
padding: 0.04
- name: katana_gripper_link
padding: 0.02
- name: katana_l_finger_link
padding: 0.02
- name: katana_r_finger_link
padding: 0.02
- name: kurtana_baseplate_link
- name: laser
- name: kurtana_pole_link
- name: kurtana_innerpole_stretch_link
2 | No.2 Revision |
In config/sensors_rgbd.yaml
(file specified in launch/<robot>_moveit_sensor_manager.launch
) replace
- sensor_type: point_cloud_sensor
with
- sensor_plugin:
occupancy_map_monitor/PointCloudOctoapUpdateroccupancy_map_monitor/PointCloudOctomapUpdater
Hint from MoveIt Google Group (sorry not enough karma to publish links...)
Here my working sensors_rgbd.yaml
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /kinect/depth_registered/points
max_range: 5.0
frame_subsample: 1
point_subsample: 1
self_mask:
min_sensor_dist: .8
self_see_default_padding: .04
self_see_default_scale: 1.0
self_see_links:
- name: katana_internal_controlbox_link
- name: katana_base_link
- name: katana_motor1_pan_link
- name: katana_motor2_lift_link
padding: 0.06
- name: katana_motor3_lift_link
padding: 0.06
- name: katana_motor4_lift_link
padding: 0.06
- name: katana_motor5_wrist_roll_link
padding: 0.04
- name: katana_gripper_link
padding: 0.02
- name: katana_l_finger_link
padding: 0.02
- name: katana_r_finger_link
padding: 0.02
- name: kurtana_baseplate_link
- name: laser
- name: kurtana_pole_link
- name: kurtana_innerpole_stretch_link