diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index 55f3ffa3..94392157 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -58,10 +58,20 @@ Send commands to a differential drive vehicle and listen to its odometry. ros2 launch ros_gz_sim_demos diff_drive.launch.xml -Then 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}}" +This demo also shows the use of custom QoS parameters. The commands are +subscribed to as "reliable", so trying to publish "best-effort" commands +won't work. See the difference between: + + ros2 topic pub /model/vehicle_blue/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0}, angular: {z: 0.0}}" --qos-reliability reliable + +And + + ros2 topic pub /model/vehicle_blue/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0}, angular: {z: 0.0}}" --qos-reliability best_effort + ![](images/diff_drive_demo.png) ## Depth camera diff --git a/ros_gz_sim_demos/config/diff_drive.yaml b/ros_gz_sim_demos/config/diff_drive.yaml index 37c8d229..cc6d36e7 100644 --- a/ros_gz_sim_demos/config/diff_drive.yaml +++ b/ros_gz_sim_demos/config/diff_drive.yaml @@ -1,36 +1,24 @@ # Diff drive configuration. -- ros_topic_name: "/model/vehicle_blue/cmd_vel" - gz_topic_name: "/model/vehicle_blue/cmd_vel" +- topic_name: "/model/vehicle_blue/cmd_vel" ros_type_name: "geometry_msgs/msg/Twist" gz_type_name: "gz.msgs.Twist" - subscriber_queue: 5 - publisher_queue: 6 - lazy: false + lazy: true direction: ROS_TO_GZ -- ros_topic_name: "/model/vehicle_blue/odometry" - gz_topic_name: "/model/vehicle_blue/odometry" +- topic_name: "/model/vehicle_blue/odometry" ros_type_name: "nav_msgs/msg/Odometry" gz_type_name: "gz.msgs.Odometry" - subscriber_queue: 5 - publisher_queue: 6 - lazy: false + lazy: true direction: GZ_TO_ROS -- ros_topic_name: "/model/vehicle_green/cmd_vel" - gz_topic_name: "/model/vehicle_green/cmd_vel" +- topic_name: "/model/vehicle_green/cmd_vel" ros_type_name: "geometry_msgs/msg/Twist" gz_type_name: "gz.msgs.Twist" - subscriber_queue: 5 - publisher_queue: 6 - lazy: false + lazy: true direction: ROS_TO_GZ -- ros_topic_name: "/model/vehicle_green/odometry" - gz_topic_name: "/model/vehicle_green/odometry" +- topic_name: "/model/vehicle_green/odometry" ros_type_name: "nav_msgs/msg/Odometry" gz_type_name: "gz.msgs.Odometry" - subscriber_queue: 5 - publisher_queue: 6 - lazy: false + lazy: true direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/diff_drive.launch.xml b/ros_gz_sim_demos/launch/diff_drive.launch.xml index 02e6f750..61a1159c 100644 --- a/ros_gz_sim_demos/launch/diff_drive.launch.xml +++ b/ros_gz_sim_demos/launch/diff_drive.launch.xml @@ -1,6 +1,14 @@ - - + +