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 ships with simulation-ready robot models for two platforms: the Rover Zero 4WD and the Leo Rover (with multiple sensor head configurations). SDF model files for the Rover Zero are located in ros2_ws/src/roverrobotics_ros2/roverrobotics_description/urdf/, while Leo Rover SDF variants live in ros2_ws/src/roverrobotics_ros2/leo_description/sdf/. Each platform is launched by a dedicated launch file in ros2_ws/src/roverrobotics_ros2/roverrobotics_gazebo/launch/.

Rover Zero 4WD

The Rover Zero 4WD is the primary research platform used in the DUnE benchmark experiments. It is a four-wheel-drive skid-steer rover with a forward-facing camera and a LIDAR scanner.

Model File

roverrobotics_description/urdf/camera_rover_4wd.sdf

Launch File

4wd_rover_gazebo.launch.py

Gazebo Entity Name

rover_zero4wd

Sensors

Forward RGB camera + 2D LIDAR scanner
The robot is spawned at position (0, 0, 1.0) in the world frame by default. The spawn step in the launch file uses ros_gz_sim create:
gz_spawn_entity = Node(
    package='ros_gz_sim',
    executable='create',
    arguments=[
        '-file', os.path.join(
            get_package_share_directory('roverrobotics_description'),
            'urdf', 'camera_rover_4wd.sdf'),
        '-name', 'rover_zero4wd',
        '-allow_renaming', 'true',
        '-x', '0',
        '-y', '0',
        '-z', '1.0',
    ],
    output='screen'
)
The entity name rover_zero4wd is used throughout the ROS 2 stack — including the pose bridge node (ign_ros2_pose_topic.py), metrics logger, and RL environment reset commands. Do not rename this entity without updating all downstream references.

Leo Rover

The Leo Rover is a compact four-wheeled rover from Leo Rover (Poland) adapted for Gazebo Fortress simulation. In RoboTerrain it serves as the primary platform for the Active Vision for Social Navigation (AVSN) pipeline, outfitted with a fisheye camera that provides approximately 160° field of view across six rectified windows. The Leo Rover SDF files reside in ros2_ws/src/roverrobotics_ros2/leo_description/sdf/. In the Leo Rover launch files the robot is spawned as entity leo_rover at position (0, 0, 1.0):
gz_spawn_entity = Node(
    package='ros_gz_sim',
    executable='create',
    arguments=[
        '-file', os.path.join(
            get_package_share_directory('leo_description'),
            'sdf', 'leo_sim_fisheye.sdf'),
        '-name', 'leo_rover',
        '-allow_renaming', 'true',
        '-x', '0',
        '-y', '0',
        '-z', '1.0',
    ],
    output='screen'
)

Leo Rover Sensor Configurations

RoboTerrain provides seven SDF files for the Leo Rover in leo_description/sdf/. Select the appropriate file in the launch file’s gz_spawn_entity node.
SDF FileSensorsPrimary Use Case
leo_sim.sdfBase Leo Rover without extra sensorsDefault Leo Rover simulation (Leo_rover_gazebo.launch.py)
leo_sim_fisheye.sdfFisheye wide-angle cameraAVSN pipeline — six rectified 320×320 windows at ~160° FOV
leo_lidar.sdf2D LIDARStandard LiDAR-based navigation and obstacle avoidance
leo_depth.sdfDepth camera (RGBD)Depth-based perception and Nav2 costmap generation
leo_AV_Lidar.sdfLIDAR + active vision headActive vision research requiring both range data and gaze control
leo_sim_ODE.sdfBase Leo Rover with ODE physics solverPhysics-solver comparison experiments
leo_sim_works.sdfVerified working baseline configurationReference model for debugging simulation issues
Launch FileDefault SDFNotes
Leo_rover_gazebo.launch.pyleo_sim.sdfBase Leo Rover simulation
Leo_rover_lidar.launch.pyleo_lidar.sdfLIDAR-only configuration
Leo_rover_depth.launch.pyleo_depth.sdfDepth camera configuration
Leo_rover_fisheye.launch.pyleo_sim_fisheye.sdfFisheye camera; used by the AVSN DreamerV3 agent
leo_nav2_lidar_launch.pyNav2 stack with LIDAR
leo_nav2_depth.launch.pyNav2 stack with depth camera

ROS 2 Bridge Topics

Both the Rover Zero and Leo Rover launch files configure a ros_gz_bridge node (parameter_bridge) that translates Ignition Gazebo messages to standard ROS 2 topics. The table below lists all bridged topics from the actual arguments=[] in 4wd_rover_gazebo.launch.py and Leo_rover_fisheye.launch.py.
ROS 2 TopicMessage TypeDirectionDescription
/cmd_velgeometry_msgs/msg/TwistBidirectional (@)Velocity command input from the RL agent or Nav2
/clockrosgraph_msgs/msg/ClockGazebo → ROS ([)Simulation clock for use_sim_time
/odometry/wheelsnav_msgs/msg/OdometryBidirectional (@)Wheel odometry from the differential drive plugin
/tftf2_msgs/msg/TFMessageGazebo → ROS ([)Transform tree from Ignition pose messages
/joint_statessensor_msgs/msg/JointStateGazebo → ROS ([)Joint state information
/scansensor_msgs/msg/LaserScanBidirectional (@)2D LIDAR scan (Rover Zero and LIDAR Leo variants; commented out in fisheye launch)
/imu/datasensor_msgs/msg/ImuBidirectional (@)IMU acceleration and orientation
/camera/image_rawsensor_msgs/msg/ImageBidirectional (@)Raw camera image (or fisheye frame for Leo fisheye)
/camera_infosensor_msgs/msg/CameraInfoBidirectional (@)Camera intrinsic parameters
/world/default/dynamic_pose/infogeometry_msgs/msg/PoseArrayGazebo → ROS ([)Full world dynamic pose information — used by the Rover Zero pipeline
/world/inspect/dynamic_pose/infogeometry_msgs/msg/PoseArrayGazebo → ROS ([)Full world dynamic pose information — used by the Leo Rover fisheye pipeline
The Leo Rover fisheye launch file additionally bridges per-actor pose topics and the robot reset service:
# Inspect world actor pose topics (Leo_rover_fisheye.launch.py)
'/linear_actor/pose@geometry_msgs/msg/Pose[gz.msgs.Pose',
'/diag_actor/pose@geometry_msgs/msg/Pose[gz.msgs.Pose',
'/triangle_actor/pose@geometry_msgs/msg/Pose[gz.msgs.Pose',

# Robot pose reset service
'/world/inspect/set_pose@ros_gz_interfaces/srv/SetEntityPose',

Differential Drive Plugin

The Leo Rover’s wheel drive is implemented via a custom Gazebo Fortress system plugin located at:
ros2_ws/src/leo_simulator-ros2/leo_gz_plugins/src/differential_system.cpp
This C++ plugin implements the Ignition Gazebo ISystemPreUpdate interface and translates incoming /cmd_vel Twist messages into individual wheel torque commands for the Leo Rover’s four-wheel-drive configuration. It is compiled as part of the leo_gz_plugins package during colcon build.
When working with the SAC/PPO RL agents, the metrics node subscribes to /scan, /imu/data, /world/default/dynamic_pose/info, and /odometry/wheels. Ensure these bridge topics are active (i.e., the bridge node is running) before starting any training or evaluation scripts.

Build docs developers (and LLMs) love