@@ -9,9 +9,9 @@ RobotReadServiceImpl::RobotReadServiceImpl(std::shared_ptr<rclcpp::Node> node)
99 DeclareROSParameter (" topic_pose" , " /tcp_pose" , " [str] Init; Sub: topic with the TCP pose data." );
1010 DeclareROSParameter (" topic_wrench" , " /wrench" , " [str] Init; Sub: topic with the F/T data." );
1111 DeclareROSParameter (" topic_joints" , " /joint_states" , " [str] Init; Sub: topic with the joint states." );
12- DeclareROSParameter (" topic_camera_scene" , " /cam_scene_rgb /image_rect" , " [str] Camera scene image topic" );
13- DeclareROSParameter (" topic_camera_right" , " /cam_tool_right/image_rect " , " [str] Camera scene image topic" );
14- DeclareROSParameter (" topic_camera_left" , " /cam_tool_left/image_rect " , " [str] Camera scene image topic" );
12+ DeclareROSParameter (" topic_camera_scene" , " /cam_scene/rgb /image_rect" , " [str] Camera scene image topic" );
13+ DeclareROSParameter (" topic_camera_right" , " /cam_tool_right/image_raw " , " [str] Camera scene image topic" );
14+ DeclareROSParameter (" topic_camera_left" , " /cam_tool_left/image_raw " , " [str] Camera scene image topic" );
1515
1616
1717 pose_sub_ = node_->create_subscription <geometry_msgs::msg::PoseStamped>(
@@ -195,15 +195,15 @@ grpc::Status RobotReadServiceImpl::GetAllVis(
195195
196196 {
197197 std::lock_guard<std::mutex> lock (pose_mutex_);
198- FillProtoPose (pose_data_, response->mutable_pose ());
198+ FillProtoPose (pose_data_, response->mutable_robot_state ()-> mutable_pose ());
199199 }
200200 {
201201 std::lock_guard<std::mutex> lock (wrench_mutex_);
202- FillProtoWrench (wrench_data_, response->mutable_wrench ());
202+ FillProtoWrench (wrench_data_, response->mutable_robot_state ()-> mutable_wrench ());
203203 }
204204 {
205205 std::lock_guard<std::mutex> lock (joint_state_mutex_);
206- FillProtoJointState (joint_state_data_, response->mutable_joint_state ());
206+ FillProtoJointState (joint_state_data_, response->mutable_robot_state ()-> mutable_joint_state ());
207207 }
208208 {
209209 std::lock_guard<std::mutex> lock (image_scene_mutex_);
0 commit comments