Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/jackvice/RoboTerrain/llms.txt

Use this file to discover all available pages before exploring further.

RoboTerrain uses a layered topic architecture that connects three distinct systems: the Ignition Gazebo simulator, the RL training agent, and the MetricsNode monitoring system. Gazebo publishes raw sensor and state data (odometry, LIDAR, IMU, camera frames, ground-truth pose) which are bridged into the ROS 2 graph via ros_gz_bridge. The RL agent consumes these topics to build observations and publishes velocity commands back to the robot. In parallel, the MetricsNode subscribes to a subset of these topics to compute collision, smoothness, and traversal metrics that are streamed to CSV for offline analysis. The PoseConverterNode (ign_ros2_Nav2_topics.py) sits between Gazebo and the rest of the stack, translating raw Gazebo dynamic-pose messages into standard ROS 2 types and broadcasting the corresponding TF transform tree.

Simulation Bridge Topics

The ros_gz_bridge node translates topics between the Ignition Gazebo message system and ROS 2. The bridge arguments use @ for bidirectional topics, [ for Gazebo → ROS 2 (subscribe from Gazebo), and ] for ROS 2 → Gazebo (publish to Gazebo). The table below documents every bridged topic in 4wd_rover_gazebo.launch.py.
TopicROS 2 Message TypeDirectionIgnition TypeDescription
/cmd_velgeometry_msgs/msg/TwistBidirectional (@)ignition.msgs.TwistLinear and angular velocity commands sent to the robot drive system
/clockrosgraph_msgs/msg/ClockGazebo → ROS 2 ([)ignition.msgs.ClockSimulation clock; consumed by all nodes running with use_sim_time:=true
/odometry/wheelsnav_msgs/msg/OdometryBidirectional (@)ignition.msgs.OdometryWheel-encoder odometry published by the Gazebo differential drive plugin
/tftf2_msgs/msg/TFMessageGazebo → ROS 2 ([)ignition.msgs.Pose_VRobot joint and link transforms; populates the TF tree for sensor fusion
/joint_statessensor_msgs/msg/JointStateGazebo → ROS 2 ([)gz.msgs.ModelPer-joint position, velocity, and effort values for all robot joints
/scansensor_msgs/msg/LaserScanBidirectional (@)gz.msgs.LaserScan2-D LIDAR scan data; used by MetricsNode for collision detection and by Nav2 for obstacle avoidance
/imu/datasensor_msgs/msg/ImuBidirectional (@)gz.msgs.IMURaw IMU linear acceleration and angular velocity; used by MetricsNode for smoothness and terrain-roughness metrics
/camera/image_rawsensor_msgs/msg/ImageBidirectional (@)gz.msgs.ImageRGB camera frames from the onboard camera; used by vision-based RL policies
/camera_infosensor_msgs/msg/CameraInfoBidirectional (@)gz.msgs.CameraInfoCamera intrinsic calibration data accompanying /camera/image_raw
/world/default/dynamic_pose/infogeometry_msgs/msg/PoseArrayGazebo → ROS 2 ([)ignition.msgs.Pose_VGround-truth poses of all entities in the default world; consumed by PoseConverterNode to derive /rover/pose_array
The /scan topic is not bridged in Leo_rover_fisheye.launch.py because the fisheye model (leo_sim_fisheye.sdf) does not include a 2-D LIDAR sensor. Check which launch file your configuration uses before relying on /scan.
The ten topics listed above are the only topics bridged in 4wd_rover_gazebo.launch.py. Other launch files such as Leo_rover_depth.launch.py and Leo_rover_fisheye.launch.py bridge additional topics (depth camera point clouds, actor poses, set-pose services) that are specific to those robot and world variants and are not part of the 4WD rover bridge configuration.

Robot Control Topics

These topics form the primary control interface between the RL agent and the simulated robot.
TopicROS 2 Message TypePublisherSubscriber(s)Description
/cmd_velgeometry_msgs/msg/TwistRL agent / Nav2ros_gz_bridge → Gazebo drive pluginVelocity commands. linear.x controls forward speed; angular.z controls yaw rate. Commands are forwarded directly to Gazebo via the bridge.
/rover/pose_arraygeometry_msgs/msg/PoseArrayPoseConverterNodeRL agent, MetricsNodeGround-truth robot pose expressed as a PoseArray with a single element in frame world. Published over a BEST_EFFORT QoS profile at approximately 50 Hz (20 ms timer).
/odom_ground_truthnav_msgs/msg/OdometryPoseConverterNodeNav2 stack, logging toolsPlanar-projected odometry derived from the Gazebo dynamic-pose stream. Roll and pitch are zeroed; only x, y, and yaw are propagated. Covariance is set to 0.01 on diagonal terms.

When running leo_nav2_lidar_launch.py, the full Nav2 stack is activated. These topics are standard Nav2 interfaces and are consumed or produced by the Nav2 servers launched in that file.
TopicROS 2 Message TypeDirectionDescription
/scansensor_msgs/msg/LaserScan→ Nav2LIDAR scan fed to the DWB local planner and costmap layers
/odom_ground_truthnav_msgs/msg/Odometry→ Nav2Bridged from Gazebo; used as the odometry source in place of /odometry/wheels in the Nav2 LIDAR configuration
/cmd_velgeometry_msgs/msg/TwistNav2 → robotVelocity commands output by the DWB controller server
/goal_posegeometry_msgs/msg/PoseStampedExternal → Nav22-D navigation goal; can be published from RViz2 or the RL agent
/tftf2_msgs/msg/TFMessagePoseConverterNode → Nav2odombase_footprint transform broadcast by the pose converter; consumed by all Nav2 costmap layers
The Nav2 configuration uses the odom frame as the global frame for mapless navigation (no AMCL or map server). The global planner is SmacPlanner2D (MOORE grid search) and the local planner is DWB (Dynamic Window Approach). See leo_nav2_lidar_params.yaml for full planner parameters.

World-Specific Service Topics

Each world variant exposes a pose-reset service through the bridge:
ServiceTypeWorld
/world/inspect/set_poseros_gz_interfaces/srv/SetEntityPoseinspect
/world/default/set_poseros_gz_interfaces/srv/SetEntityPosedefault
/world/moon/set_poseros_gz_interfaces/srv/SetEntityPosemoon
These services allow the RL training harness to teleport the robot to a new start pose at episode reset without restarting the simulation.

QoS Profiles

Most topics in RoboTerrain use the ROS 2 default Reliable QoS profile with a history depth of 10. The /rover/pose_array topic is an exception — it is published and subscribed with a BEST_EFFORT profile to minimise latency at high update rates.

BEST_EFFORT Profile — /rover/pose_array

from rclpy.qos import QoSProfile, ReliabilityPolicy, HistoryPolicy

qos_profile = QoSProfile(
    reliability=ReliabilityPolicy.BEST_EFFORT,
    history=HistoryPolicy.KEEP_LAST,
    depth=1
)
The publisher (PoseConverterNode) and all subscribers (MetricsNode, RL agent) must use matching QoS settings. Mismatched reliability policies will result in silent connection failures — the subscriber will appear connected but will receive no messages.
The KEEP_LAST history with depth=1 means only the most recent pose is retained in the queue. Combined with the 20 ms publish timer in PoseConverterNode, this ensures subscribers always receive the freshest ground-truth pose with minimal buffering delay.
If you add a new subscriber to /rover/pose_array, always specify the BEST_EFFORT QoS profile explicitly. ROS 2 will not warn you about the mismatch at node startup.

Build docs developers (and LLMs) love