From 5e0c49bb72da758b9e0de7baf6d9bf9f95f54c77 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Carlos=20Ag=C3=BCero?= Date: Mon, 16 Dec 2024 11:43:18 +0100 Subject: [PATCH] Refactor battery demo (#633) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Carlos Agüero --- ros_gz_sim_demos/README.md | 24 +++++++++++------------ ros_gz_sim_demos/config/battery.yaml | 12 ++++++++++++ ros_gz_sim_demos/launch/battery.launch.py | 19 +++++++----------- 3 files changed, 31 insertions(+), 24 deletions(-) create mode 100644 ros_gz_sim_demos/config/battery.yaml diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index 6c612de3..e3b64601 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -28,6 +28,18 @@ And ![](images/air_pressure_demo.png) +## Battery + +Get the current state of a battery. + + ros2 launch ros_gz_sim_demos battery.launch.py + +Then send a command so the vehicle moves and drains the battery. + + ros2 topic pub /model/vehicle_blue/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0}, angular: {z: 0.5}}" + +![](images/battery_demo.png) + ## Camera Publishes RGB camera image and info. @@ -169,18 +181,6 @@ Using Gazebo Sim plugin: ![](images/rgbd_camera_demo.png) -## Battery - -Get the current state of a battery. - - ros2 launch ros_gz_sim_demos battery.launch.py - -Then send a command so the vehicle moves and drains the battery - - ros2 topic pub /model/vehicle_blue/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0}, angular: {z: 0.5}}" - -![](images/battery_demo.png) - ## Robot description publisher Leverage the robot description publisher to spawn a new urdf model in gazebo and diff --git a/ros_gz_sim_demos/config/battery.yaml b/ros_gz_sim_demos/config/battery.yaml new file mode 100644 index 00000000..9f6494bb --- /dev/null +++ b/ros_gz_sim_demos/config/battery.yaml @@ -0,0 +1,12 @@ +# Battery 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/battery/linear_battery/state" + ros_type_name: "sensor_msgs/msg/BatteryState" + gz_type_name: "gz.msgs.BatteryState" + lazy: true + direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/battery.launch.py b/ros_gz_sim_demos/launch/battery.launch.py index 8abe8eff..a0da9fdf 100644 --- a/ros_gz_sim_demos/launch/battery.launch.py +++ b/ros_gz_sim_demos/launch/battery.launch.py @@ -15,20 +15,20 @@ import os from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.actions import IncludeLaunchDescription from launch.conditions import IfCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration - from launch_ros.actions import Node +from ros_gz_bridge.actions import RosGzBridge def generate_launch_description(): pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') # RQt rqt = Node( @@ -40,6 +40,7 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration('rqt')) ) + # Gazebo gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), @@ -49,21 +50,15 @@ def generate_launch_description(): ) # Bridge - bridge = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - arguments=[ - '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist', - '/model/vehicle_blue/battery/linear_battery/state@sensor_msgs/msg/BatteryState@' - 'gz.msgs.BatteryState' - ], - output='screen' + ros_gz_bridge = RosGzBridge( + bridge_name='ros_gz_bridge', + config_file=os.path.join(pkg_ros_gz_sim_demos, 'config', 'battery.yaml'), ) return LaunchDescription([ gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), - bridge, + ros_gz_bridge, rqt ])