Gazebo Garden
4/20/25 TODO complete migration to Gazebo Garden
https://github.com/oc-robotics/differential_drive_robot/tree/jason
Update
lidar.xacro
https://github.com/joshnewans/articubot_one/blob/new_gazebo/description/lidar.xacroUpdate
camera.xacro
https://github.com/joshnewans/articubot_one/blob/new_gazebo/description/camera.xacroUpdate launch file https://github.com/joshnewans/articubot_one/blob/new_gazebo/launch/launch_sim.launch.py
Rename
gz_bridge.yml
togz_bridge.yaml
and update with:(https://discord.com/channels/1204942703243173918/1362926788468015285/1363385886317744283)Update
obstacle_worlds.sdf
to include sensor pluginsUpdate RViz configuration to visualize camera and LiDAR data
Get wheels moving in RViz
Katelynn: Needs big googly eyes
Update lidar
- Update
lidar.xacro
lidar.xacro
<?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" > <joint name="laser_joint" type="fixed"> <parent link="chassis"/> <child link="laser_frame"/> <origin xyz="0.122 0 0.212" rpy="0 0 0"/> </joint> <link name="laser_frame"> <visual> <geometry> <cylinder radius="0.05" length="0.04"/> </geometry> <material name="red"/> </visual> <visual> <origin xyz="0 0 -0.05"/> <geometry> <cylinder radius="0.01" length="0.1"/> </geometry> <material name="black"/> </visual> <collision> <geometry> <cylinder radius="0.05" length="0.04"/> </geometry> </collision> <xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05"> <origin xyz="0 0 0" rpy="0 0 0"/> </xacro:inertial_cylinder> </link> <gazebo reference="laser_frame"> <material>Gazebo/Black</material> <sensor name="gpu_lidar" type="gpu_lidar"> <pose relative_to="lidar_frame"> 0 0 0 0 0 0 </pose> <visualize>true</visualize> <update_rate>10</update_rate> <lidar> <scan> <horizontal> <samples>360</samples> <min_angle>-3.14</min_angle> <max_angle>3.14</max_angle> </horizontal> </scan> <range> <min>0.3</min> <max>12</max> </range> </lidar> <topic>lidar</topic> <gz_frame_id>laser_frame</gz_frame_id> </sensor> </gazebo> </robot>
- Check
scan
topic
ros2 topic info /scan
Type: sensor_msgs/msg/LaserScan
Publisher count: 1
Subscription count: 0
ros2 topic echo /scan
Add Sim Camera
-
Resources
-
Create
description/camera.xacro
file
description/camera.xacro
<?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" > <joint name="camera_joint" type="fixed"> <parent link="chassis"/> <child link="camera_link"/> <origin xyz="0.276 0 0.181" rpy="0 0.18 0"/> </joint> <link name="camera_link"> <visual> <geometry> <box size="0.010 0.03 0.03"/> </geometry> <material name="black"/> </visual> <visual> <origin xyz="0 0 -0.05"/> <geometry> <cylinder radius="0.002" length="0.1"/> </geometry> <material name="black"/> </visual> </link> <joint name="camera_optical_joint" type="fixed"> <parent link="camera_link"/> <child link="camera_link_optical"/> <origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/> </joint> <link name="camera_link_optical"></link> <gazebo reference="camera_link"> <material>Gazebo/Black</material> <sensor name="camera" type="camera"> <pose> 0 0 0 0 0 0 </pose> <visualize>true</visualize> <update_rate>10</update_rate> <camera> <camera_info_topic>camera/camera_info</camera_info_topic> <horizontal_fov>1.089</horizontal_fov> <image> <format>R8G8B8</format> <width>640</width> <height>480</height> </image> <clip> <near>0.05</near> <far>8.0</far> </clip> </camera> <topic>camera/image_raw</topic> <gz_frame_id>camera_link_optical</gz_frame_id> </sensor> </gazebo> </robot>
- Test image topic
ros2 topic echo /camera/image_raw
header:
stamp:
sec: 142
nanosec: 500000000
frame_id: camera_link_optical
height: 480
width: 640
encoding: rgb8
is_bigendian: 0
step: 1920
data:
- 218
- 218
- 218
- 218
- 218
- 218
- 218
...
RViz
- Update
diff-drive.rviz
diff-drive.rviz
Panels: - Class: rviz_common/Displays Help Height: 78 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /Status1 - /RobotModel1/Description Topic1 - /TF1 - /LaserScan1 - /Image1 - /Image1/Topic1 Splitter Ratio: 0.5 Tree Height: 433 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties Expanded: - /2D Goal Pose1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 - Class: rviz_common/Views Expanded: - /Current View1 Name: Views Splitter Ratio: 0.5 - Class: rviz_common/Time Experimental: false Name: Time SyncMode: 0 SyncSource: "" Visualization Manager: Class: "" Displays: - Alpha: 0.5 Cell Size: 1 Class: rviz_default_plugins/Grid Color: 160; 160; 164 Enabled: true Line Style: Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 Offset: X: 0 Y: 0 Z: 0 Plane: XY Plane Cell Count: 10 Reference Frame: <Fixed Frame> Value: true - Alpha: 1 Class: rviz_default_plugins/RobotModel Collision Enabled: false Description File: "" Description Source: Topic Description Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable Value: /robot_description Enabled: true Links: All Links Enabled: true Expand Joint Details: false Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order base_link: Alpha: 1 Show Axes: false Show Trail: false camera_link: Alpha: 1 Show Axes: false Show Trail: false Value: true camera_link_optical: Alpha: 1 Show Axes: false Show Trail: false caster_wheel: Alpha: 1 Show Axes: false Show Trail: false Value: true chassis: Alpha: 1 Show Axes: false Show Trail: false Value: true laser_frame: Alpha: 1 Show Axes: false Show Trail: false Value: true left_wheel: Alpha: 1 Show Axes: false Show Trail: false Value: true right_wheel: Alpha: 1 Show Axes: false Show Trail: false Value: true Mass Properties: Inertia: false Mass: false Name: RobotModel TF Prefix: "" Update Interval: 0 Value: true Visual Enabled: true - Class: rviz_default_plugins/TF Enabled: true Frame Timeout: 15 Frames: All Enabled: true base_link: Value: true camera_link: Value: true camera_link_optical: Value: true caster_wheel: Value: true chassis: Value: true laser_frame: Value: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: base_link: chassis: camera_link: camera_link_optical: {} caster_wheel: {} laser_frame: {} Update Interval: 0 Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: Max Value: 10 Min Value: -10 Value: true Axis: Z Channel Name: intensity Class: rviz_default_plugins/LaserScan Color: 255; 255; 255 Color Transformer: "" Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Max Intensity: 4096 Min Color: 0; 0; 0 Min Intensity: 0 Name: LaserScan Position Transformer: "" Selectable: true Size (Pixels): 3 Size (m): 0.009999999776482582 Style: Flat Squares Topic: Depth: 5 Durability Policy: Volatile Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable Value: /scan Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz_default_plugins/Image Enabled: true Max Value: 1 Median window: 5 Min Value: 0 Name: Image Normalize Range: true Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable Value: /camera/image_raw Value: true Enabled: true Global Options: Background Color: 48; 48; 48 Fixed Frame: base_link Frame Rate: 30 Name: root Tools: - Class: rviz_default_plugins/Interact Hide Inactive Objects: true - Class: rviz_default_plugins/MoveCamera - Class: rviz_default_plugins/Select - Class: rviz_default_plugins/FocusCamera - Class: rviz_default_plugins/Measure Line color: 128; 128; 0 - Class: rviz_default_plugins/SetInitialPose Covariance x: 0.25 Covariance y: 0.25 Covariance yaw: 0.06853891909122467 Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable Value: /initialpose - Class: rviz_default_plugins/SetGoal Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable Value: /goal_pose - Class: rviz_default_plugins/PublishPoint Single click: true Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable Value: /clicked_point Transformation: Current: Class: rviz_default_plugins/TF Value: true Views: Current: Class: rviz_default_plugins/Orbit Distance: 8.984903335571289 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: X: 0.05397603660821915 Y: 0.08794327825307846 Z: 0.05943708494305611 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 Pitch: 0.22020354866981506 Target Frame: <Fixed Frame> Value: Orbit (rviz) Yaw: 2.755408763885498 Saved: ~ Window Geometry: Displays: collapsed: false Height: 987 Hide Left Dock: false Hide Right Dock: false Image: collapsed: false QMainWindow State: 000000ff00000000fd00000004000000000000015600000341fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000023a000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000027b000001010000002800ffffff000000010000010f00000341fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b00000341000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007740000003efc0100000002fb0000000800540069006d00650100000000000007740000025300fffffffb0000000800540069006d00650100000000000004500000000000000000000005030000034100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false Width: 1908 X: 0 Y: 0
- Run
RViz
rviz2 -d src/differential_drive_robot/config/diff-drive.rviz
gz-bridge.yaml
gz-bridge.yaml
--- - ros_topic_name: "clock" gz_topic_name: "clock" ros_type_name: "rosgraph_msgs/msg/Clock" gz_type_name: "gz.msgs.Clock" direction: GZ_TO_ROS # gz topic published by Sensors plugin - ros_topic_name: "scan" gz_topic_name: "scan" ros_type_name: "sensor_msgs/msg/LaserScan" gz_type_name: "gz.msgs.LaserScan" direction: GZ_TO_ROS # gz topic published by Sensors plugin (Camera) - ros_topic_name: "camera/camera_info" gz_topic_name: "camera/camera_info" ros_type_name: "sensor_msgs/msg/CameraInfo" gz_type_name: "gz.msgs.CameraInfo" direction: GZ_TO_ROS # # gz topic published by DiffDrive plugin # - ros_topic_name: "odom" # gz_topic_name: "odom" # ros_type_name: "nav_msgs/msg/Odometry" # gz_type_name: "gz.msgs.Odometry" # direction: GZ_TO_ROS # # gz topic published by DiffDrive plugin # - ros_topic_name: "tf" # gz_topic_name: "tf" # ros_type_name: "tf2_msgs/msg/TFMessage" # gz_type_name: "gz.msgs.Pose_V" # direction: GZ_TO_ROS # # gz topic subscribed to by DiffDrive plugin # - ros_topic_name: "diff_cont/cmd_vel_unstamped" # gz_topic_name: "cmd_vel" # ros_type_name: "geometry_msgs/msg/Twist" # gz_type_name: "gz.msgs.Twist" # direction: ROS_TO_GZ # # gz topic published by JointState plugin # - ros_topic_name: "joint_states" # gz_topic_name: "joint_states" # ros_type_name: "sensor_msgs/msg/JointState" # gz_type_name: "gz.msgs.Model" # direction: GZ_TO_ROS - ros_topic_name: "/cmd_vel" gz_topic_name: "/model/my_bot/cmd_vel" ros_type_name: "geometry_msgs/msg/Twist" gz_type_name: "gz.msgs.Twist" direction: ROS_TO_GZ - ros_topic_name: "/odom" gz_topic_name: "/model/my_bot/odometry" ros_type_name: "nav_msgs/msg/Odometry" gz_type_name: "gz.msgs.Odometry" direction: GZ_TO_ROS - ros_topic_name: "/joint_states" gz_topic_name: "/world/empty/model/my_bot/joint_state" ros_type_name: "sensor_msgs/msg/JointState" gz_type_name: "gz.msgs.Model" direction: GZ_TO_ROS
Launch file
launch/launch_sim.launch.py
import os from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): package_name='differential_drive_robot' rsp = IncludeLaunchDescription( PythonLaunchDescriptionSource([os.path.join( get_package_share_directory(package_name),'launch','rsp.launch.py' )]), launch_arguments={'use_sim_time': 'true'}.items() ) default_world = os.path.join( get_package_share_directory(package_name), 'worlds', 'obstacle_world.sdf' # 'empty.world' ) world = LaunchConfiguration('world') world_arg = DeclareLaunchArgument( 'world', default_value=default_world, description='World to load' ) # Include the Gazebo launch file, provided by the ros_gz_sim package gazebo = IncludeLaunchDescription( PythonLaunchDescriptionSource([os.path.join( get_package_share_directory('ros_gz_sim'), 'launch', 'gz_sim.launch.py')]), launch_arguments={'gz_args': ['-r -v4 ', world], 'on_exit_shutdown': 'true'}.items() ) # Run the spawner node from the ros_gz_sim package spawn_entity = Node(package='ros_gz_sim', executable='create', arguments=['-topic', 'robot_description', '-name', 'my_bot', '-z', '0.1'], output='screen') # # Bridge for cmd_vel and other topics # bridge = Node( # package='ros_gz_bridge', # executable='parameter_bridge', # parameters=[{ # 'config_file': os.path.join(get_package_share_directory(package_name), 'config', 'bridge.yaml'), # }], # output='screen' # ) bridge_params = os.path.join(get_package_share_directory(package_name),'config','gz_bridge.yaml') ros_gz_bridge = Node( package="ros_gz_bridge", executable="parameter_bridge", arguments=[ '--ros-args', '-p', f'config_file:={bridge_params}', ] ) ros_gz_image_bridge = Node( package="ros_gz_image", executable="image_bridge", arguments=["/camera/image_raw"] ) # Launch them all! return LaunchDescription([ rsp, world_arg, gazebo, spawn_entity, ros_gz_bridge, ros_gz_image_bridge ])
Run simulation
- Update
obstacle_worlds.sdf
to include sensor plugins
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
- Drive the robot
```bash
ros2 run teleop_twist_keyboard teleop_twist_keyboard
- List gazebo topics
gz topic -l
/camera/camera_info
/camera/image_raw
/clock
/gazebo/resource_paths
/gui/camera/pose
/gui/record_video/stats
/keyboard/keypress
/model/my_bot/cmd_vel
/model/my_bot/joint_state
/model/my_bot/odometry
/model/my_bot/tf
/scan
/scan/points
/sensors/marker
/stats
/world/empty/clock
/world/empty/dynamic_pose/info
/world/empty/pose/info
/world/empty/scene/deletion
/world/empty/scene/info
/world/empty/state
/world/empty/stats
- List ros topics
ros2 topic list
/camera/camera_info
/camera/image_raw
/camera/image_raw/compressed
/camera/image_raw/compressedDepth
/camera/image_raw/theora
/clock
/cmd_vel
/joint_states
/odom
/parameter_events
/robot_description
/rosout
/scan
/tf
/tf_static