From ba05c7fe91b7491b2bf254f6460b94efdfaf0360 Mon Sep 17 00:00:00 2001
From: Ridhwan Luthra <luthraridhwan@gmail.com>
Date: Tue, 13 Nov 2018 16:04:41 +0530
Subject: [PATCH] Edits to match perception tutorial (#4)

Rename camera to match perception tutorial: https://github.com/ros-planning/moveit_tutorials/pull/178.
---
 config/sensors_kinect_depthmap.yaml   | 3 ++-
 config/sensors_kinect_pointcloud.yaml | 3 ++-
 launch/sensor_manager.launch.xml      | 6 +++++-
 3 files changed, 9 insertions(+), 3 deletions(-)

diff --git a/config/sensors_kinect_depthmap.yaml b/config/sensors_kinect_depthmap.yaml
index 68b7f06..9538fe0 100644
--- a/config/sensors_kinect_depthmap.yaml
+++ b/config/sensors_kinect_depthmap.yaml
@@ -1,10 +1,11 @@
 sensors:
   - sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
-    image_topic: /head_mount_kinect/depth_registered/image_raw
+    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
diff --git a/config/sensors_kinect_pointcloud.yaml b/config/sensors_kinect_pointcloud.yaml
index 1033442..92e7095 100644
--- a/config/sensors_kinect_pointcloud.yaml
+++ b/config/sensors_kinect_pointcloud.yaml
@@ -1,8 +1,9 @@
 sensors:
   - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
-    point_cloud_topic: /head_mount_kinect/depth_registered/points
+    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
diff --git a/launch/sensor_manager.launch.xml b/launch/sensor_manager.launch.xml
index 616fcf0..67aa2fd 100644
--- a/launch/sensor_manager.launch.xml
+++ b/launch/sensor_manager.launch.xml
@@ -2,9 +2,13 @@
 
   <!-- This file makes it easy to include the settings for sensor managers -->
 
+  <!-- Param for kinect config -->
+  <rosparam command="load" file="$(find panda_moveit_config)/config/sensors_kinect_pointcloud.yaml" />
+
   <!-- Params for the octomap monitor -->
   <!--  <param name="octomap_frame" type="string" value="some frame in which the robot moves" /> -->
-  <param name="octomap_resolution" type="double" value="0.025" />
+  <param name="octomap_frame" type="string" value="camera_rgb_optical_frame" />
+  <param name="octomap_resolution" type="double" value="0.05" />
   <param name="max_range" type="double" value="5.0" />
 
   <!-- Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter -->
-- 
GitLab