Skip to content

Commit

Permalink
Update robot camera topic names
Browse files Browse the repository at this point in the history
  • Loading branch information
LihanChen2004 committed Jan 18, 2025
1 parent 3a97db6 commit 1730e43
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
4 changes: 2 additions & 2 deletions config/ros_gz_bridge.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
gz_type_name: "ignition.msgs.Model"
direction: "GZ_TO_ROS"

- ros_topic_name: "/<robot_name>/front_camera/image"
- ros_topic_name: "/<robot_name>/front_industrial_camera/image"
gz_topic_name: "/world/default/model/<robot_name>/link/front_industrial_camera/sensor/front_industrial_camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"
Expand All @@ -36,7 +36,7 @@
gz_type_name: "ignition.msgs.IMU"
direction: "GZ_TO_ROS"

- ros_topic_name: "/<robot_name>/front_camera/camera_info"
- ros_topic_name: "/<robot_name>/front_industrial_camera/camera_info"
gz_topic_name: "/world/default/model/<robot_name>/link/front_industrial_camera/sensor/front_industrial_camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "ignition.msgs.CameraInfo"
Expand Down
2 changes: 1 addition & 1 deletion rviz/visualize.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ Visualization Manager:
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /red_standard_robot1/front_camera/image
Value: /red_standard_robot1/front_industrial_camera/image
Value: true
Visibility:
TF: false
Expand Down
2 changes: 1 addition & 1 deletion scripts/player_web/main_no_vision.py
Original file line number Diff line number Diff line change
Expand Up @@ -341,7 +341,7 @@ def ros_info_thread(node, robot_name):
for robot_name in robot_names:
node.create_subscription(
Image,
"/%s/front_camera/image" % (robot_name),
"/%s/front_industrial_camera/image" % (robot_name),
send_img_callback(robot_name),
45,
)
Expand Down
2 changes: 1 addition & 1 deletion scripts/player_web/main_vision.py
Original file line number Diff line number Diff line change
Expand Up @@ -394,7 +394,7 @@ def ros_info_thread(node, robot_name):
for robot_name in robot_names:
node.create_subscription(
Image,
"/%s/front_camera/image" % (robot_name),
"/%s/front_industrial_camera/image" % (robot_name),
send_img_callback(robot_name),
45,
)
Expand Down

0 comments on commit 1730e43

Please sign in to comment.