Skip to content

Commit

Permalink
Add ground truth odometry (#10)
Browse files Browse the repository at this point in the history
  • Loading branch information
MarqRazz authored Dec 11, 2024
1 parent 212e88c commit 3898d06
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 6 deletions.
1 change: 1 addition & 0 deletions c300/c300_bringup/launch/gazebo_c300.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,7 @@ def generate_launch_description():
"/scan@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan",
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
"/imu@sensor_msgs/msg/Imu[ignition.msgs.IMU",
"/gt_odom@nav_msgs/msg/Odometry[gz.msgs.Odometry",
],
output="screen",
)
Expand Down
24 changes: 19 additions & 5 deletions c300/c300_description/urdf/c300.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,17 @@
<robot name="c300_gazebo" xmlns:xacro="http://ros.org/wiki/xacro" xmlns:gz="http://gazebosim.org/schema">

<!--
Gazebo plugins can only be included once. Use this xacro as an example of how to run ros2_control in Gazebo.
Required Gazebo plugins:
- gz_ros2_control::GazeboSimROS2ControlPlugin
required to read and publish the robots joint states
-->
Gazebo plugins can only be included once. Use this xacro to start the required plugins to simulate the mobile base in Gazebo.
Required Gazebo plugins:
- gz_ros2_control::GazeboSimROS2ControlPlugin
required to read and publish the robots joint states
- gz::sim::systems::Sensors
required to simulate the Lidar and any camera sensors
- gz::sim::systems::Imu
required to simulate the IMU sensor
- gz::sim::systems::OdometryPublisher
optional plugin to publish ground truth odometry data
-->
<xacro:macro name="c300_gazebo" params="simulation_controllers">

<gazebo>
Expand All @@ -22,6 +28,14 @@ Required Gazebo plugins:
<render_engine>ogre2</render_engine>
</plugin>
<plugin filename="gz-sim-imu-system" name="gz::sim::systems::Imu"/>
<plugin filename="gz-sim-odometry-publisher-system"
name="gz::sim::systems::OdometryPublisher">
<odom_frame>odom</odom_frame>
<robot_base_frame>base_link</robot_base_frame>
<odom_publish_frequency>50</odom_publish_frequency>
<odom_topic>gt_odom</odom_topic>
<dimensions>3</dimensions>
</plugin>
</gazebo>

<gazebo reference="imu_link">
Expand Down
3 changes: 2 additions & 1 deletion c3pzero/c3pzero_bringup/launch/gazebo_c3pzero.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ def generate_launch_description():
"-y",
"0.0",
"-z",
"0.0",
"0.172",
"-R",
"0.0",
"-P",
Expand All @@ -156,6 +156,7 @@ def generate_launch_description():
"/left_arm_wrist_camera/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked",
"/left_arm_wrist_camera/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo",
"/scan@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan",
"/gt_odom@nav_msgs/msg/Odometry[gz.msgs.Odometry",
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
],
remappings=[
Expand Down

0 comments on commit 3898d06

Please sign in to comment.