Skip to content

Commit

Permalink
Merge branch 'ros2' into caguero/camera_demo_v2
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Dec 16, 2024
2 parents 8412e89 + 5e0c49b commit 4d717ee
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 24 deletions.
24 changes: 12 additions & 12 deletions ros_gz_sim_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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
Expand Down
12 changes: 12 additions & 0 deletions ros_gz_sim_demos/config/battery.yaml
Original file line number Diff line number Diff line change
@@ -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
19 changes: 7 additions & 12 deletions ros_gz_sim_demos/launch/battery.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand All @@ -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')),
Expand All @@ -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/[email protected]',
'/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
])

0 comments on commit 4d717ee

Please sign in to comment.