This repository contains the package with the robot description of CC8 Rover (Version: 2022-2023).
This package enables the integration of a rover model into an empty world simulated in Gazebo and configures the necessary controllers for joint movement. It is designed to be compatible with ROS1 and Gazebo version 11.11.
The robot description (URDF) was generated using a Fusion 360 addon. This tool exports a URDF model with accurate inertial and visual parameters directly derived from the original CAD design, ensuring fidelity. Additionally, the package configures specific controllers for each joint, enabling a complete and realistic simulation.
The robot is described using a URDF file (/urdf/cc8.xacro) written in a macro language called xacro in which all links and joints are defined with their parent-child relationships.
In the hierarchy of links within the model, the initial link must be defined without inertial properties and is referred to as
base_footprint
. The URDF format currently does not support defining a closed kinematic loop within this tree structure. Therefore, the mechanical function of the differential bar is only represented in Gazebo through a plugin (libleo_gazebo_differential_plugin.so
).
NOTE: When using this URDF model outside of Gazebo simulations, an alternative system must be implemented to replicate the function of the differential bar, ensuring the coordinated rotation of
rocker_joint_L
androcker_joint_R
. Without this mechanism,base_link
is free to rotate when exposed to gravitational forces.
- cc8.xacro: URDF file written in a macro language called Xacro in which all links and joints are defined with their parent-child relationships.
- cc8.gazebo: Included in
cc8.xacro
. It defines the Gazebo plugins used and properties for the links. Gazebo plugins used:- gazebo_ros_control: This plugin allows defining and loading all controllers used in the Gazebo simulation. It is important to define the robot's namespace, as this is required during the controller loading phase (Gazebo guide for
ros_control
). - rocker_differential: A plugin specific to the Leo Rover model.
- gazebo_ros_control: This plugin allows defining and loading all controllers used in the Gazebo simulation. It is important to define the robot's namespace, as this is required during the controller loading phase (Gazebo guide for
- cc8.trans:Included in
cc8.xacro
. This file defines all the transmission characteristics of the joints and their actuators. When defining a transmission, ensure thehardwareInterface
matches the type of controller chosen for that joint to maintain consistency. - zed2.xacro: Included in
cc8.xacro
. This file contains two macros.zed2
describes the model of the Zed2i stereo camera, defining the links and joints used to position the optical reference frames of the two cameras.zed2_gazebo
allows the simulation of the stereo camera within Gazebo by defining the necessary sensors and plugins along with all associated parameters. This setup enables the availability of key outputs during a Gazebo simulation, such as RGB images from both cameras, depth data, point clouds, internal IMU data, etc. (These data are published on the same topics typically used by the real Zed camera).zed2.xacro
was copied from theleo_description
package of Leo Rover.
This directory contains all the meshes for the individual links and the stereo camera. These meshes are referenced in cc8.xacro
, which provides the overall description of the rover. The formats used are .stl
and .dae
, with the latter being particularly useful for importing textures of individual components (e.g., wheel colors, etc.). These meshes are used exclusively for visualizing the components and are not used to determine contact between different links, as this could slow down the simulation. If contacts need to be considered, it is recommended to create meshes with simpler geometries.
-
To start the simulation (in a paused state) of the rover within Gazebo in an empty world, the
cc8_gazebo.launch
file must be used. This launch file, in turn, includes two other launch files. The first one launched isempty_world.launch
(not included in this package but found ingazebo_ros
), which loads the empty world. The second,spawn_robot.launch
, loads the rover model into the newly created world.spawn_robot.launch
itself includes two launch files:spawn_model.launch
, which loads the URDF model built fromcc8.xacro
, andspawn_controllers.launch
(ROS control), which is responsible for loading the controllers needed to operate the four steering joints and the six wheels through thespawn_controller
node. Additionally,spawn_controllers.launch
loads the type of controller and the respective PID constants (kp, ki, kd) into the ROS parameter server by reading thecontroller.yaml
file located in the/config
directory.spawn_controllers.launch
also starts therobot_state_publisher
node, which uses the URDF specified by therobot_description
parameter and joint positions from the/cc8/joint_states
topic to calculate the robot's forward kinematics and publish the results viatf
(robot_state_publisher). -
This launch file allows you to open Rviz and visualize the state of the rover through RobotModel and TF.
Note: This launch starts the
robot_state_publisher
node, which is also started byspawn_controller
, where it is necessary for the simulation in Gazebo. To avoid a conflict between the two nodes, if you want to monitor the state of the rover in Rviz, you can usecc8_display_norsp.launch
, in which therobot_state_publisher
node is not started.
This directory contains controller.yaml
, where the names and parameters of the controllers are defined.
- joint_state_controller: The controller responsible for publishing the state of the various joints.
- steering_{...}_position_controller: The four controllers used to independently control the four steering joints.
- wheel_joint_{...}_position_controller: The six controllers used to independently control the six wheels.
The structure of this file specifies the robot's namespace initially (in this case, cc8, this is declared in cc8.gazebo
when using the gazebo_ros_control
plugin). This is followed by a list of all the controllers used. Each controller is defined as follows:
{controller_name (e.g., steering_FL_position_controller)}:
type: {controller type (e.g., effort_controllers/JointPositionController)}
joint: {joint name as specified in the URDF file (e.g., steering_FL)}
pid: {PID controller constants}
There are different types of controllers that can receive an input, which may be a position, velocity, or torque. Based on this input, the controller determines the error, calculated as the difference between the input (the reference) and the current state of the joint. The output of the controller can be a position, velocity, or torque, which is then used as input for the simulation. An example of a control scheme is shown in the figure below.
In this example, the type of joint controller used is:
effort_controllers/JointPositionController
effort_controller
indicates that the output of the PID controller is a torque, which is the actual command sent to the joint in the simulation.JointPositionController
indicates that the error is calculated as the positional difference between the reference position published on the topic and the actual position represented by the joint state.
In general, other types of control schemes can be used, such as:
effort_controllers/JointEffortController
effort_controllers/JointVelocityController
velocity_controllers/JointVelocityController
velocity_controllers/JointPositionController
- etc...
The type of controller chosen must be consistent with what is declared in cc8.trans
. The type of HardwareInterface
must match the type of controller. For example, if we have a controller type that sends torque as input to the joint (as in the previous example), then within the transmission element, the hardwareInterface
should be specified as follows:
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
- Select the appropriate controllers to enable position control for the steering joints and velocity control for the wheels.
- Perform PID tuning to optimize the parameters for each control loop.
- Since each joint has a dedicated topic for command publication, a ROS node must be developed to manage the publication of commands. This node should handle position commands for the steering joints and velocity commands for the wheels. Development can be based on the existing firmware_CC8.py.
- Create a simulation world representing the Mars Yard 2024 environment.