Skip to content

Commit

Permalink
Tweaks
Browse files Browse the repository at this point in the history
Signed-off-by: Carlos Agüero <[email protected]>
  • Loading branch information
caguero committed Nov 22, 2024
1 parent 75217b1 commit 79ece9e
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 23 deletions.
12 changes: 11 additions & 1 deletion ros_gz_sim_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
28 changes: 8 additions & 20 deletions ros_gz_sim_demos/config/diff_drive.yaml
Original file line number Diff line number Diff line change
@@ -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
12 changes: 10 additions & 2 deletions ros_gz_sim_demos/launch/diff_drive.launch.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,14 @@
<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" />
<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"
bridge_params="'qos_overrides./model/vehicle_blue.subscriber.reliability': 'reliable',
'qos_overrides./model/vehicle_green.subscriber.reliability': 'reliable'" />
<node pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share ros_gz_sim_demos)/rviz/diff_drive.rviz" />
<executable cmd="gz sim -g" />
</launch>

0 comments on commit 79ece9e

Please sign in to comment.