Skip to content

Commit

Permalink
Add sensor config files for perception tutorial
Browse files Browse the repository at this point in the history
  • Loading branch information
rickstaa authored and rhaschke committed Sep 28, 2021
1 parent f0c2bca commit 2aaa01d
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 24 deletions.
23 changes: 0 additions & 23 deletions config/sensors_3d.yaml

This file was deleted.

11 changes: 11 additions & 0 deletions config/sensors_kinect_depthmap.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
sensors:
- sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
image_topic: /camera/depth_registered/image_raw
queue_size: 5
near_clipping_plane_distance: 0.3
far_clipping_plane_distance: 5.0
shadow_threshold: 0.2
padding_scale: 4.0
padding_offset: 0.03
max_update_rate: 1.0
filtered_cloud_topic: filtered_cloud
9 changes: 9 additions & 0 deletions config/sensors_kinect_pointcloud.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /camera/depth_registered/points
max_range: 5.0
point_subsample: 1
padding_offset: 0.1
padding_scale: 1.0
max_update_rate: 1.0
filtered_cloud_topic: filtered_cloud
5 changes: 4 additions & 1 deletion launch/sensor_manager.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@
<!-- This file makes it easy to include the settings for sensor managers -->

<!-- Params for 3D sensors config -->
<rosparam command="load" file="$(find panda_moveit_config)/config/sensors_3d.yaml" />
<arg name="sensor_type" default="pointcloud"/>
<rosparam if="$(eval arg('sensor_type') == 'point_cloud')" command="load" file="$(find panda_moveit_config)/config/sensors_kinect_pointcloud.yaml" />
<rosparam unless="$(eval arg('sensor_type') == 'point_cloud')" command="load" file="$(find panda_moveit_config)/config/sensors_kinect_depthmap.yaml" />

<!-- Params for the octomap monitor -->
<!-- <param name="octomap_frame" type="string" value="some frame in which the robot moves" /> -->
<param name="octomap_frame" type="string" value="camera_rgb_optical_frame" />
<param name="octomap_resolution" type="double" value="0.025" />
<param name="max_range" type="double" value="5.0" />

Expand Down

0 comments on commit 2aaa01d

Please sign in to comment.