Skip to content

Commit

Permalink
Copter: default topic names
Browse files Browse the repository at this point in the history
  • Loading branch information
pedro-fuoco committed Sep 1, 2023
1 parent a329ffa commit 3985297
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 13 deletions.
4 changes: 2 additions & 2 deletions ardupilot_gz_bringup/config/iris_bridge.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
- ros_topic_name: "tf"
- ros_topic_name: "gz/tf"
gz_topic_name: "/model/iris/pose"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
- ros_topic_name: "tf_static"
- ros_topic_name: "gz/tf_static"
gz_topic_name: "/model/iris/pose_static"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
Expand Down
6 changes: 3 additions & 3 deletions ardupilot_gz_bringup/config/iris_lidar_bridge.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
- ros_topic_name: "tf"
- ros_topic_name: "gz/tf"
gz_topic_name: "/model/iris/pose"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
- ros_topic_name: "tf_static"
- ros_topic_name: "gz/tf_static"
gz_topic_name: "/model/iris/pose_static"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
Expand All @@ -31,7 +31,7 @@
gz_type_name: "gz.msgs.IMU"
direction: GZ_TO_ROS

- ros_topic_name: "laser/scan"
- ros_topic_name: "scan"
gz_topic_name: "/lidar"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
Expand Down
4 changes: 0 additions & 4 deletions ardupilot_gz_bringup/launch/robots/iris.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -131,10 +131,6 @@ def generate_launch_description():
parameters=[
{"robot_description": robot_desc},
],
remappings=[
("/tf", "/ap/tf"),
("/tf_static", "/ap/tf_static"),
],
)

# Bridge.
Expand Down
4 changes: 0 additions & 4 deletions ardupilot_gz_bringup/launch/robots/iris_lidar.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -134,10 +134,6 @@ def generate_launch_description():
parameters=[
{"robot_description": robot_desc},
],
remappings=[
("/tf", "/ap/tf"),
("/tf_static", "/ap/tf_static"),
],
)

# Bridge.
Expand Down

0 comments on commit 3985297

Please sign in to comment.