From 8d3f2c1a1a8aecb8abee592c9af0d06671c32938 Mon Sep 17 00:00:00 2001 From: Michel Breyer Date: Sat, 11 Sep 2021 21:02:14 +0200 Subject: [PATCH] Match realsense depth topic name --- cfg/active_grasp.yaml | 4 ++-- scripts/bt_sim_node.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/cfg/active_grasp.yaml b/cfg/active_grasp.yaml index 278dd6c..c92437d 100644 --- a/cfg/active_grasp.yaml +++ b/cfg/active_grasp.yaml @@ -1,6 +1,6 @@ bt_sim: gui: True - cam_noise: True + cam_noise: False scene: test1.yaml grasp_controller: @@ -12,7 +12,7 @@ grasp_controller: camera: frame_id: camera_depth_optical_frame info_topic: /camera/depth/camera_info - depth_topic: /camera/depth/image_raw + depth_topic: /camera/depth/image_rect_raw min_z_dist: 0.3 vgn: diff --git a/scripts/bt_sim_node.py b/scripts/bt_sim_node.py index 062fd66..bdb2e8c 100755 --- a/scripts/bt_sim_node.py +++ b/scripts/bt_sim_node.py @@ -297,7 +297,7 @@ class CameraPlugin(Plugin): def init_publishers(self): topic = self.name + "/depth/camera_info" self.info_pub = rospy.Publisher(topic, CameraInfo, queue_size=10) - topic = self.name + "/depth/image_raw" + topic = self.name + "/depth/image_rect_raw" self.depth_pub = rospy.Publisher(topic, Image, queue_size=10) def update(self):