Skip to content

Commit 954df6d

Browse files
authored
Copter: fix iris TF and orientation (#5)
Update world and model - Rename world to 'map'. - Publish 3D odometry. Move rviz config to separate folder - Update composite example - Remap /tf and /tf_static from robot_state_publisher. - Update rviz config. - Add test mission. Include iris model with gimbal - Replace in-place copy of model with include. Update model orientation - Update orientation of models to ENU. - Update rviz config. Signed-off-by: Rhys Mainwaring <[email protected]>
1 parent 4687800 commit 954df6d

File tree

7 files changed

+368
-674
lines changed

7 files changed

+368
-674
lines changed

ardupilot_gz_bringup/CMakeLists.txt

+7
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,13 @@ install(
2222
DESTINATION share/${PROJECT_NAME}/config
2323
)
2424

25+
# Install project rviz files.
26+
install(
27+
DIRECTORY
28+
rviz/
29+
DESTINATION share/${PROJECT_NAME}/rviz
30+
)
31+
2532
# --------------------------------------------------------------------------- #
2633
# Build tests.
2734

ardupilot_gz_bringup/config/iris.rviz

-331
This file was deleted.

ardupilot_gz_bringup/config/iris_bridge.yaml

+8-8
Original file line numberDiff line numberDiff line change
@@ -4,16 +4,16 @@
44
ros_type_name: "rosgraph_msgs/msg/Clock"
55
gz_type_name: "gz.msgs.Clock"
66
direction: GZ_TO_ROS
7-
- ros_topic_name: "/iris/odometry"
8-
gz_topic_name: "/model/iris/odometry"
9-
ros_type_name: "nav_msgs/msg/Odometry"
10-
gz_type_name: "gz.msgs.Odometry"
11-
direction: GZ_TO_ROS
127
- ros_topic_name: "/joint_states"
13-
gz_topic_name: "/world/demo/model/iris/joint_state"
8+
gz_topic_name: "/world/map/model/iris/joint_state"
149
ros_type_name: "sensor_msgs/msg/JointState"
1510
gz_type_name: "gz.msgs.Model"
1611
direction: GZ_TO_ROS
12+
- ros_topic_name: "/odometry"
13+
gz_topic_name: "/model/iris/odometry"
14+
ros_type_name: "nav_msgs/msg/Odometry"
15+
gz_type_name: "gz.msgs.Odometry"
16+
direction: GZ_TO_ROS
1717
- ros_topic_name: "/tf"
1818
gz_topic_name: "/model/iris/pose"
1919
ros_type_name: "tf2_msgs/msg/TFMessage"
@@ -25,12 +25,12 @@
2525
gz_type_name: "gz.msgs.Pose_V"
2626
direction: GZ_TO_ROS
2727
- ros_topic_name: "/camera/image"
28-
gz_topic_name: "/world/demo/model/iris/link/tilt_link/sensor/camera/image"
28+
gz_topic_name: "/world/map/model/iris/link/tilt_link/sensor/camera/image"
2929
ros_type_name: "sensor_msgs/msg/Image"
3030
gz_type_name: "gz.msgs.Image"
3131
direction: GZ_TO_ROS
3232
- ros_topic_name: "/camera/camera_info"
33-
gz_topic_name: "/world/demo/model/iris/link/tilt_link/sensor/camera/camera_info"
33+
gz_topic_name: "/world/map/model/iris/link/tilt_link/sensor/camera/camera_info"
3434
ros_type_name: "sensor_msgs/msg/CameraInfo"
3535
gz_type_name: "gz.msgs.CameraInfo"
3636
direction: GZ_TO_ROS
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
QGC WPL 110
2+
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 583.989990 1
3+
1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363174 149.165358 10.000000 1
4+
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363220 149.165248 10.000000 1
5+
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363175 149.165139 10.000000 1
6+
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363264 149.165192 10.000000 1
7+
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363356 149.165137 10.000000 1
8+
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363310 149.165250 10.000000 1
9+
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363355 149.165358 10.000000 1
10+
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363264 149.165302 10.000000 1
11+
9 0 0 177 1.000000 -1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1

0 commit comments

Comments
 (0)