Skip to content

Commit 5cf7033

Browse files
committed
Fix typos
1 parent 8a77a27 commit 5cf7033

File tree

2 files changed

+10
-13
lines changed

2 files changed

+10
-13
lines changed

aegis_grpc/proto_aegis_grpc/v1/robot_srvs.proto

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,16 +22,13 @@ message RobotState {
2222
Pose pose = 1;
2323
Wrench wrench = 2;
2424
JointState joint_state = 3;
25-
Image image = 4;
2625
}
2726

2827
message RobotStateVis {
29-
Pose pose = 1;
30-
Wrench wrench = 2;
31-
JointState joint_state = 3;
32-
Image image_scene = 4;
33-
Image image_right = 5;
34-
Image image_left = 6;
28+
RobotState robot_state = 1;
29+
Image image_scene = 2;
30+
Image image_right = 3;
31+
Image image_left = 4;
3532
}
3633

3734
service RobotControlService {

aegis_grpc/src/robot_read_service.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Comments
 (0)