Leo Rover ROS API Reference
Subscribed topics​
-
cmd_vel(geometry_msgs/msg/Twist)Target velocity of the Rover. Only
linear.x,linear.y(if using the mecanum wheels mode) andangular.zare used. -
heading_controller/cmd_vel(geometry_msgs/msg/Twist)Target velocity for the Rover when using heading control. Publish to this topic instead of
cmd_velif you want the Rover to automatically correct its steering and maintain its heading while driving straight or making wide turns. Onlylinear.xandangular.zare used. This topic is not supported when using mecanum wheels.warningCannot be used at the same time as other
cmdtopics. -
firmware/wheel_{FL,RL,FR,RR}/cmd_pwm_duty(std_msgs/msg/Float32)Target PWM duty cycle for each wheel motor.
warningCannot be used at the same time as other
cmdtopics. -
firmware/wheel_{FL,RL,FR,RR}/cmd_velocity(std_msgs/msg/Float32)Target velocity of the individual wheels.
warningCannot be used at the same time as other
cmdtopics.
Published Topics​
-
merged_odom(nav_msgs/msg/Odometry)Merged odometry calculated from wheel encoders and the onboard IMU.
infoThis is the preferred topic to use for odometry data. Use this topic instead of
wheel_odomorfirmware/wheel_odom. -
wheel_odom(nav_msgs/msg/Odometry)Odometry calculated from wheel encoders.
-
imu/data(sensor_msgs/msg/Imu)Filtered readings from the onboard IMU. The filter does 2 things:
- Adds a dynamic bias to the gyroscope readings.
- Adds an estimated orientation by fusing the accelerometer and gyroscope data.
infoThis is the preferred topic to use for IMU data. Use this topic instead of
imu/data_raworfirmware/imu -
imu/data_raw(sensor_msgs/msg/Imu)Raw gyroscope and accelerometer readings from the onboard IMU.
-
imu/rpy(geometry_msgs/msg/Vector3Stamped)Roll, pitch and yaw angles calculated from the IMU data.
-
camera/image_raw(sensor_msgs/msg/Image)Raw, unprocessed image data from the camera.
-
camera/camera_info(sensor_msgs/msg/CameraInfo)Intrinsic and extrinsic parameters of the camera, such as calibration data.
-
camera/image_color(sensor_msgs/msg/Image)Color image data from the camera. No different from
camera/image_raw. -
camera/image_color/compressed(sensor_msgs/msg/CompressedImage)Compressed color image data from the camera.
-
camera/image_mono(sensor_msgs/msg/Image)Monochrome (grayscale) image data from the camera.
-
camera/image_mono/compressed(sensor_msgs/msg/CompressedImage)Compressed monochrome (grayscale) image data from the camera.
-
camera/image_rect(sensor_msgs/msg/Image)Rectified (undistorted) monochrome image data from the camera.
-
camera/image_rect/compressed(sensor_msgs/msg/CompressedImage)Compressed rectified monochrome image data from the camera.
-
camera/image_rect_color(sensor_msgs/msg/Image)Rectified (undistorted) color image data from the camera.
-
camera/image_rect_color/compressed(sensor_msgs/msg/CompressedImage)Compressed rectified color image data from the camera.
-
firmware/battery(std_msgs/msg/Float32)Current battery voltage reading.
-
firmware/battery_averaged(std_msgs/msg/Float32)Battery voltage estimated from averaging readings from last 30 seconds.
-
joint_states(sensor_msgs/msg/JointState)Current state of the robot joints.
-
robot_description(std_msgs/msg/String)The URDF description of the robot.
-
/parameter_events(rcl_interfaces/msg/ParameterEvent)Parameter events (additions, changes or deletions) from all the running ROS nodes.
-
/rosout(rcl_interfaces/msg/Log)Logs from all the running ROS nodes.
-
/tf,/tf_static(tf2_msgs/msg/TFMessage)Relationships between TF frames in the ROS network.
These topics are used by the tf2 library.
Services​
-
reset_odometry(std_srvs/srv/Trigger)Reset odometry position.
-
camera/set_camera_info(sensor_msgs/srv/SetCameraInfo)Set onboard camera calibration parameters.
-
firmware/get_board_type(std_srvs/srv/Trigger)Get the type of the controller board.
-
firmware/get_firmware_version(std_srvs/srv/Trigger)Get the version of the firmware running on the controller board.
-
firmware/reset_board(std_srvs/srv/Trigger)Perform software reset of the controller board.
-
imu_filter/reset_calibration(std_srvs/srv/Trigger)Reset the IMU calibration. This will reset the dynamic gyroscope bias.
-
system/reboot(std_srvs/srv/Trigger)Perform reboot of the onboard computer's system.
-
system/shutdown(std_srvs/srv/Trigger)Perform shutdown of the onboard computer's system.
Parameters​
All of the default parameters for the standard nodes running on the system can
be overridden in the /etc/ros/parameter_overrides.yaml file. Check the file
for more details and examples.
The parameters not marked as read-only can also be changed at runtime using
command line tools such as ros2 param set or graphical tools like rqt with
the rqt_reconfigure plugin (run rqt -s rqt_reconfigure).
camera​
-
role(type:string, read-only, default:video)Which StreamRole to use. (possible choices:
raw,still,video,viewfinder) -
format(type:string, read-only, default:BGR888)The pixel format of the camera stream. For possible values, check picamera2 documentation (Appendix A).
-
width,height(type:int, read-only, default:1024,768)The width and height of the camera stream in pixels.
-
sensor_mode(type:string, read-only, default:'')The desired raw sensor format resolution (format:
width:height). If empty, the default resolution will be used. -
orientation(type:int, read-only, default:0)The orientation of the camera in degrees. Possible values: 0, 90, 180, 270.
-
frame_id(type:string, read-only, default:camera_optical_frame)The TF frame associated with the camera stream.
Apart from the aforementioned parameters, the camera node also translates some of the libcamera controls into ROS parameters. The camera controls are documented in picamera2 documentation (Appendix C).
camera/debayer​
-
.image_color.compressed.jpeg_quality(type:int, default:80)The quality of the JPEG compression for the color image. Range: 0-100.
-
.image_mono.compressed.jpeg_quality(type:int, default:80)The quality of the JPEG compression for the monochrome image. Range: 0-100.
camera/rectify_mono​
-
.image_rect_color.compressed.jpeg_quality(type:int, default:80)The quality of the JPEG compression for the rectified color image. Range: 0-100.
camera/rectify_color​
-
.image_rect.compressed.jpeg_quality(type:int, default:80)The quality of the JPEG compression for the rectified monochrome image. Range: 0-100.
firmware​
The parameters for the firmware node are not meant to be changed directly by
users. Instead, set the corresponding parameters on the
firmware_parameter_bridge node (it mirrors the firmware parameters and
forwards updates to firmware).
-
wheels.encoder_resolution(type:float, default:878.4)The resolution of the wheel encoder in counts per rotation.
-
wheels.torque_constant(type:float, default:1.17647)The torque (in newton-meters) produced by the wheel per 1 Ampere of winding current.
-
wheels.pid.kp(type:float, default:2.64)The proportional gain of the PID regulator.
-
wheels.pid.ki(type:float, default:42.24)The integral gain of the PID regulator.
-
wheels.pid.kd(type:float, default:0.11)The derivative gain of the PID regulator.
The PID loop controls the voltage applied to the wheels based on the difference between the target velocity and the actual velocity.
The output voltage at time is calculated as:
where:
- is the time in seconds,
- is the velocity error at time (target velocity - actual velocity),
- is the proportional gain (
wheels.pid.kp), - is the integral gain (
wheels.pid.ki), - is the derivative gain (
wheels.pid.kd).
For example, if the target velocity is 1.0 and the actual velocity
is 0.8 , the velocity error is 0.2 .
A of 10.0 would contribute 2.0 to the output voltage, a of 50.0
would contribute 10.0 per second of sustained error.
The firmware employs anti-windup measures to prevent the integral term from
accumulating excessively when the output voltage is saturated at the maximum
available/applied voltage (e.g. limited by battery voltage and/or
wheels.max_voltage).
-
wheels.max_voltage(type:float, default:26.0)Maximum voltage (in Volts) that can be applied to the wheels. If the battery voltage is above this value, the controller will scale down the PWM duty cycle to avoid applying voltage higher than this to the wheels.
-
controller.wheel_radius(type:float, default:0.0625)The radius of the wheel in meters.
-
controller.wheel_separation(type:float, default:0.358)The distance (in meters) between the centers of the left and right wheels.
-
controller.wheel_base(type:float, default:0.3052)The distance (in meters) between the centers of the rear and front wheels.
-
controller.angular_velocity_multiplier(type:float, default:1.76)The angular velocity in
cmd_velcommand is multiplied by this parameter and the calculated odometry has its angular velocity divided by this parameter. -
controller.input_timeout(type:int, default:500)The timeout (in milliseconds) for the
cmd_velcommands. The controller will be disabled if it does not receive a command within the specified time. If set to 0, the timeout is disabled. -
controller.linear_acceleration(type:float, default:0.5)The linear acceleration (in ) applied to the robot when accelerating.
-
controller.linear_deceleration(type:float, default:2.0)The linear deceleration (in ) applied to the robot when decelerating (when the absolute linear velocity is decreasing).
-
controller.angular_acceleration(type:float, default:1.0)The angular acceleration (in ) applied to the robot when accelerating.
-
controller.angular_deceleration(type:float, default:4.0)The angular deceleration (in ) applied to the robot when decelerating (when the absolute angular velocity is decreasing).
-
battery_min_voltage(type:float, default:10.0)The voltage (in Volts) below which the battery is considered low. If the battery goes below this voltage, the LED indicator will start blinking fast.
-
mecanum_wheels(type:bool, default:false)Enables mecanum wheel functionality. When set to
true, the robot switches to mecanum wheel kinematics, enabling omnidirectional movement including lateral strafing vialinear.ycommands and adjusting odometry calculations for mecanum wheel geometry.
firmware_message_converter​
-
robot_frame_id(type:string, read-only, default:base_footprint)The TF frame associated with the robot.
-
odom_frame_id(type:string, read-only, default:odom)The TF frame associated with the odometry readings.
-
imu_frame_id(type:string, read-only, default:imu_frame)The TF frame associated with the IMU readings.
-
tf_frame_prefix(type:string, read-only, default:'')The prefix added to the published TF frames.
-
wheel_joint_names(type:string[], read-only, default:['wheel_FL_joint', 'wheel_RL_joint', 'wheel_FR_joint', 'wheel_RR_joint'])The names of the wheel joints used in the
joint_statestopic. The order of the names is: front left, rear left, front right, rear right. -
wheel_odom_twist_covariance_diagonal(type:float[], read-only, default:[0.0001, 0.0001, 0, 0, 0, 0.001])The diagonal of the covariance matrix for the standard wheel odometry twist readings. The size of the array must be 6, representing the variances for the linear x, linear y, linear z, angular x, angular y and angular z axes.
-
wheel_odom_mecanum_twist_covariance_diagonal(type:float[], read-only, default:[0.0001, 0, 0, 0, 0, 0.001])The diagonal of the covariance matrix for the mecanum wheel odometry twist readings. The size of the array must be 6, representing the variances for the linear x, linear y, linear z, angular x, angular y and angular z axes.
-
imu_angular_velocity_covariance_diagonal(type:float[], read-only, default:[1.0e-06, 1.0e-06, 1.0e-05])The diagonal of the covariance matrix for the IMU angular velocity readings. The size of the array must be 3, representing the variances for the x, y and z axes.
-
imu_linear_acceleration_covariance_diagonal(type:float[], read-only, default:[0.001, 0.001, 0.001])The diagonal of the covariance matrix for the IMU linear acceleration readings. The size of the array must be 3, representing the variances for the x, y and z axes.
heading_controller​
-
linear_hold_deadband(type:float, default:0.05)Minimum absolute
linear.xcommand required to enable heading hold. If the command is below this value, no heading correction is applied. -
kp(type:float, default:15.0)Proportional gain used to convert heading error into
angular.zcorrection. -
max_correction(type:float, default:1.0)Maximum absolute
angular.zcorrection allowed by the heading controller. -
yaw_deadband(type:float, default:0.005)Heading error tolerance. Errors within this range produce no correction.
-
angular_hold_deadband(type:float, default:0.2)Maximum absolute
angular.zcommand still treated as heading-hold mode. Above this value, no heading correction is applied.
imu_filter​
-
gain_acc(type:float, default:0.01)Gain for the complementary filter for orientation estimation. The value must be in the range (0, 1).
-
do_adaptive_gain(type:bool, default:true)Whether to use adaptive gain for the complementary filter. If set to
true, the gain will be adjusted based on the accelerometer readings. -
bias_alpha(type:float, default:0.01)The gyroscope bias estimation gain. The value must be in the range (0, 1).
-
do_bias_estimation(type:bool, default:true)Whether to do bias estimation of the angular velocity (gyroscope readings). If set to
false, the gyroscope readings will not be filtered and will be published as is. -
do_save_bias(type:bool, read-only, default:true)Whether to periodically store the gyroscope bias on the disk and load it upon startup.
-
bias_save_period(type:int, read-only, default:120)Time interval between current imu bias save (in seconds).
-
orientation_variance(type:float, default:0.001)The variance of the orientation estimation. Will be used to fill the diagonal of the covariance matrix of the IMU orientation readings. The value must be greater than 0.
odom_filter​
-
publish_tf(type:bool, default:true)Whether to publish the TF frame for the odometry.