Skip to content

Commit

Permalink
Copter: fix iris TF and orientation (#5)
Browse files Browse the repository at this point in the history
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]>
  • Loading branch information
srmainwaring authored Apr 18, 2023
1 parent 4687800 commit 954df6d
Show file tree
Hide file tree
Showing 7 changed files with 368 additions and 674 deletions.
7 changes: 7 additions & 0 deletions ardupilot_gz_bringup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,13 @@ install(
DESTINATION share/${PROJECT_NAME}/config
)

# Install project rviz files.
install(
DIRECTORY
rviz/
DESTINATION share/${PROJECT_NAME}/rviz
)

# --------------------------------------------------------------------------- #
# Build tests.

Expand Down
331 changes: 0 additions & 331 deletions ardupilot_gz_bringup/config/iris.rviz

This file was deleted.

16 changes: 8 additions & 8 deletions ardupilot_gz_bringup/config/iris_bridge.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "gz.msgs.Clock"
direction: GZ_TO_ROS
- ros_topic_name: "/iris/odometry"
gz_topic_name: "/model/iris/odometry"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
- ros_topic_name: "/joint_states"
gz_topic_name: "/world/demo/model/iris/joint_state"
gz_topic_name: "/world/map/model/iris/joint_state"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "gz.msgs.Model"
direction: GZ_TO_ROS
- ros_topic_name: "/odometry"
gz_topic_name: "/model/iris/odometry"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
- ros_topic_name: "/tf"
gz_topic_name: "/model/iris/pose"
ros_type_name: "tf2_msgs/msg/TFMessage"
Expand All @@ -25,12 +25,12 @@
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
- ros_topic_name: "/camera/image"
gz_topic_name: "/world/demo/model/iris/link/tilt_link/sensor/camera/image"
gz_topic_name: "/world/map/model/iris/link/tilt_link/sensor/camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS
- ros_topic_name: "/camera/camera_info"
gz_topic_name: "/world/demo/model/iris/link/tilt_link/sensor/camera/camera_info"
gz_topic_name: "/world/map/model/iris/link/tilt_link/sensor/camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
direction: GZ_TO_ROS
11 changes: 11 additions & 0 deletions ardupilot_gz_bringup/config/iris_waypoints.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 583.989990 1
1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363174 149.165358 10.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363220 149.165248 10.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363175 149.165139 10.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363264 149.165192 10.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363356 149.165137 10.000000 1
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363310 149.165250 10.000000 1
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363355 149.165358 10.000000 1
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363264 149.165302 10.000000 1
9 0 0 177 1.000000 -1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
Loading

0 comments on commit 954df6d

Please sign in to comment.