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
caguero authored Dec 13, 2024
2 parents 8308b89 + f9e5409 commit 8412e89
Show file tree
Hide file tree
Showing 12 changed files with 148 additions and 249 deletions.
6 changes: 3 additions & 3 deletions ros_gz_sim_demos/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@ Using Gazebo Sim plugin:

Publishes IMU readings.

ros2 launch ros_gz_sim_demos imu.launch.py
ros2 launch ros_gz_sim_demos imu.launch.xml

![](images/imu_demo.png)

Expand All @@ -126,7 +126,7 @@ Publishes IMU readings.

Publishes magnetic field readings.

ros2 launch ros_gz_sim_demos magnetometer.launch.py
ros2 launch ros_gz_sim_demos magnetometer.launch.xml

![](images/magnetometer_demo.png)

Expand Down Expand Up @@ -208,6 +208,6 @@ and transforms of a robot in rviz.

To try the demo launch:

ros2 launch ros_gz_sim_demos tf_bridge.launch.py
ros2 launch ros_gz_sim_demos tf_bridge.launch.xml

![](images/tf_bridge.gif)
6 changes: 6 additions & 0 deletions ros_gz_sim_demos/config/imu.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# IMU configuration.
- topic_name: "/imu"
ros_type_name: "sensor_msgs/msg/Imu"
gz_type_name: "gz.msgs.IMU"
lazy: true
direction: GZ_TO_ROS
6 changes: 6 additions & 0 deletions ros_gz_sim_demos/config/magnetometer.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Magnetometer configuration.
- topic_name: "/magnetometer"
ros_type_name: "sensor_msgs/msg/MagneticField"
gz_type_name: "gz.msgs.Magnetometer"
lazy: true
direction: GZ_TO_ROS
14 changes: 14 additions & 0 deletions ros_gz_sim_demos/config/tf_bridge.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# tf_bridge configuration.
- ros_topic_name: "/joint_states"
gz_topic_name: "/world/default/model/double_pendulum_with_base0/joint_state"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "gz.msgs.Model"
lazy: true
direction: GZ_TO_ROS

- ros_topic_name: "/tf"
gz_topic_name: "/model/double_pendulum_with_base0/pose"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
lazy: true
direction: GZ_TO_ROS
78 changes: 0 additions & 78 deletions ros_gz_sim_demos/launch/imu.launch.py

This file was deleted.

13 changes: 13 additions & 0 deletions ros_gz_sim_demos/launch/imu.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>
<gz_server
world_sdf_file="sensors.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/imu.yaml"
use_composition="True" />
<node pkg="rqt_topic" exec="rqt_topic" args="-t" />
<node pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share ros_gz_sim_demos)/rviz/imu.rviz" />
<executable cmd="gz sim -g" />
</launch>
63 changes: 0 additions & 63 deletions ros_gz_sim_demos/launch/magnetometer.launch.py

This file was deleted.

12 changes: 12 additions & 0 deletions ros_gz_sim_demos/launch/magnetometer.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<launch>
<gz_server
world_sdf_file="sensors.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/magnetometer.yaml"
use_composition="True" />
<node pkg="rqt_topic" exec="rqt_topic" args="-t" />
<executable cmd="gz sim -g" />
</launch>
59 changes: 0 additions & 59 deletions ros_gz_sim_demos/launch/tf_bridge.launch.py

This file was deleted.

12 changes: 12 additions & 0 deletions ros_gz_sim_demos/launch/tf_bridge.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<launch>
<gz_server
world_sdf_file="$(find-pkg-share ros_gz_sim_demos)/models/double_pendulum_model.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/tf_bridge.yaml"
use_composition="True" />
<node pkg="rviz2" exec="rviz2" args="-d $(find-pkg-share ros_gz_sim_demos)/rviz/tf_bridge.rviz" />
<executable cmd="gz sim -g" />
</launch>
1 change: 1 addition & 0 deletions ros_gz_sim_demos/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
<exec_depend>rqt_image_view</exec_depend>
<exec_depend>rqt_plot</exec_depend>
<exec_depend>rqt_topic</exec_depend>
<exec_depend>rviz_imu_plugin</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>sdformat_urdf</exec_depend>
<exec_depend>xacro</exec_depend>
Expand Down
Loading

0 comments on commit 8412e89

Please sign in to comment.