Skip to content

Commit

Permalink
Merge branch 'ros2' into shutdown_explicitly
Browse files Browse the repository at this point in the history
  • Loading branch information
azeey authored Dec 18, 2024
2 parents 9a4ff95 + 6c0f01f commit 518d11e
Show file tree
Hide file tree
Showing 22 changed files with 464 additions and 429 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@ Iron | Garden | [humble](https://github.com/gazebosim/ros_gz/tree/iron) | only f
Iron | Harmonic | [humble](https://github.com/gazebosim/ros_gz/tree/iron) | only from source
Jazzy | Garden | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source [^2]
Jazzy | Harmonic | [jazzy](https://github.com/gazebosim/ros_gz/tree/jazzy) | https://packages.ros.org
Rolling | Fortress | [humble](https://github.com/gazebosim/ros_gz/tree/humble) | https://packages.ros.org
Rolling | Garden | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source [^2]
Rolling | Harmonic | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source
Rolling | Ionic | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | https://packages.ros.org

[^1]: Binaries for these pairings are provided from the packages.osrfoundation.org repository. Refer to https://gazebosim.org/docs/latest/ros_installation for installation instructions.
[^2]: Note that the Gazebo version on this row has reached end-of-life.
Expand Down
12 changes: 6 additions & 6 deletions ros_gz_sim_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,11 @@ Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.o

Using the regular bridge:

ros2 launch ros_gz_sim_demos camera.launch.py
ros2 launch ros_gz_sim_demos camera.launch.xml

To use a camera that only publishes information when triggered:

ros2 launch ros_gz_sim_demos triggered_camera.launch.py
ros2 launch ros_gz_sim_demos triggered_camera.launch.xml

Trigger the camera:

Expand All @@ -68,9 +68,9 @@ Trigger the camera:

Send commands to a differential drive vehicle and listen to its odometry.

ros2 launch ros_gz_sim_demos diff_drive.launch.py
ros2 launch ros_gz_sim_demos diff_drive.launch.xml

Then unpause and send a command
Then send a command

ros2 topic pub /model/vehicle_blue/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0}, angular: {z: 0.5}}"

Expand Down Expand Up @@ -114,7 +114,7 @@ GPU lidar data can be obtained as:

Using the bridge:

ros2 launch ros_gz_sim_demos gpu_lidar_bridge.launch.py
ros2 launch ros_gz_sim_demos gpu_lidar_bridge.launch.xml

*TODO*: Blocked by `ros_gz_point_cloud` [issue](https://github.com/gazebosim/ros_gz/issues/40).

Expand Down Expand Up @@ -171,7 +171,7 @@ Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.o

Using the regular bridge:

ros2 launch ros_gz_sim_demos rgbd_camera_bridge.launch.py
ros2 launch ros_gz_sim_demos rgbd_camera_bridge.launch.xml

*TODO*: Blocked by `ros_gz_point_cloud` [issue](https://github.com/gazebosim/ros_gz/issues/40).

Expand Down
12 changes: 12 additions & 0 deletions ros_gz_sim_demos/config/camera.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# Camera bridge configuration.
- topic_name: "/camera"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
lazy: true
direction: GZ_TO_ROS
36 changes: 36 additions & 0 deletions ros_gz_sim_demos/config/diff_drive.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
# Diff drive configuration.
- topic_name: "/model/vehicle_blue/cmd_vel"
ros_type_name: "geometry_msgs/msg/Twist"
gz_type_name: "gz.msgs.Twist"
lazy: true
direction: ROS_TO_GZ

- topic_name: "/model/vehicle_blue/odometry"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/model/vehicle_green/cmd_vel"
ros_type_name: "geometry_msgs/msg/Twist"
gz_type_name: "gz.msgs.Twist"
lazy: true
direction: ROS_TO_GZ

- topic_name: "/model/vehicle_green/odometry"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
lazy: true
direction: GZ_TO_ROS

- ros_topic_name: "/tf"
gz_topic_name: "/model/vehicle_green/tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS

- ros_topic_name: "/tf"
gz_topic_name: "/model/vehicle_blue/tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
12 changes: 12 additions & 0 deletions ros_gz_sim_demos/config/gpu_lidar.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# GPU lidar configuration.
- topic_name: "/lidar"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/lidar/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "gz.msgs.PointCloudPacked"
lazy: true
direction: GZ_TO_ROS
38 changes: 38 additions & 0 deletions ros_gz_sim_demos/config/rgbd_camera_bridge.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
# rgbd_camera_bridge configuration.
- ros_topic_name: "/camera/image"
gz_topic_name: "/camera"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
lazy: true
direction: GZ_TO_ROS

- ros_topic_name: "/camera/camera_info"
gz_topic_name: "/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/rgbd_camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/rgbd_camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/rgbd_camera/depth_image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/rgbd_camera/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "gz.msgs.PointCloudPacked"
lazy: true
direction: GZ_TO_ROS
18 changes: 18 additions & 0 deletions ros_gz_sim_demos/config/triggered_camera.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
# triggered_cammera configuration.
- topic_name: "/camera"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
lazy: true
direction: GZ_TO_ROS

- topic_name: "/camera/trigger"
ros_type_name: "std_msgs/msg/Bool"
gz_type_name: "gz.msgs.Boolean"
lazy: true
direction: ROS_TO_GZ
63 changes: 0 additions & 63 deletions ros_gz_sim_demos/launch/camera.launch.py

This file was deleted.

13 changes: 13 additions & 0 deletions ros_gz_sim_demos/launch/camera.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>
<gz_server
world_sdf_file="camera_sensor.sdf"
use_composition="True"
create_own_container="True" />
<ros_gz_bridge
bridge_name="ros_gz_bridge"
config_file="$(find-pkg-share ros_gz_sim_demos)/config/camera.yaml"
use_composition="True" />
<node pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share ros_gz_sim_demos)/rviz/camera.rviz" />
<node pkg="tf2_ros" exec="static_transform_publisher" args="--frame-id camera_link --child-frame-id camera/link/camera --roll 1.570796327 --yaw 1.570796327" />
<executable cmd="gz sim -g" />
</launch>
69 changes: 0 additions & 69 deletions ros_gz_sim_demos/launch/diff_drive.launch.py

This file was deleted.

17 changes: 17 additions & 0 deletions ros_gz_sim_demos/launch/diff_drive.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<launch>
<gz_server
world_sdf_file="diff_drive.sdf"
use_composition="True"
create_own_container="True" />
<ros_gz_bridge
bridge_name="ros_gz_bridge"
config_file="$(find-pkg-share ros_gz_sim_demos)/config/diff_drive.yaml"
use_composition="True">
<param name="qos_overrides./model/vehicle_blue.subscriber.reliability" value='reliable'></param>
<param name="qos_overrides./model/vehicle_green.subscriber.reliability" value='reliable'></param>
</ros_gz_bridge>
<node pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share ros_gz_sim_demos)/rviz/diff_drive.rviz" />
<node pkg="tf2_ros" exec="static_transform_publisher" args="--frame-id world --child-frame-id vehicle_green/odom --y -2" />
<node pkg="tf2_ros" exec="static_transform_publisher" args="--frame-id world --child-frame-id vehicle_blue/odom --y 2" />
<executable cmd="gz sim -g" />
</launch>
Loading

0 comments on commit 518d11e

Please sign in to comment.