Skip to main content

ROS 2 API

ROS API

Beta Release

Please be advised that the software you are about to use is a Beta version of the ROS 2 Driver for Lynx and Panther. It is functional, and the architecture will not change significantly. Although it has been tested by the Husarion team, some stability issues and bugs may still occur. We would greatly appreciate your feedback regarding the Husarion UGV ROS 2 driver. You can reach us in the following ways:

ROS 2 System Design

This section describes the ROS packages used in Husarion UGV. These packages are located in the husarion_ugv_ros GitHub repository.

Hardware Compatibility

This package supports Lynx v0.2+, Panther v1.2+. There may be small differences between robot models. This is caused by the hardware differences. Despite that, the ROS API was kept as closely matched between those revisions as possible and should be transparent in most of the use cases.

The default way to communicate with our robots is via the Robot Operating System (ROS). All the drivers were written in ROS 2 framework. The ROS API is provided by ROS packages found in the GitHub repository husarion/husarion_ugv_ros. These packages are responsible for accessing the hardware components of the robot.

The graph below represents Husarion UVG ROS system. Some topics and services have been excluded from the graph for the sake of clarity.

Husarion UVG ROS 2 System Design Diagram

ROS Interfaces

Below is information about the physical robot API. For the simulation, topics and services are identical to the physical robot, but due to certain limitations, not all interfaces are present in the simulation.

SymbolMeaning
🤖Available for physical robot
🖥️Available in simulation
⚙️Requires specific configuration

Nodes

🤖🖥️Node nameDescription
battery_driverPublishes battery state read from ADC unit.
panther_batter/battery_driver_node
controller_managerThe Controller Manager performs two main functions. First, it manages controllers and their required interfaces, handling tasks like loading, activating, deactivating, and unloading. Second, it interacts with hardware components, ensuring access to their interfaces. This node manages the: imu_broadcaster, joint_state_broadcaster, drive_controller.
controller_manager/controller_manager
drive_controllerManages mobile robots with a differential or mecanum drive depending on the configuration. It converts velocity commands for the robot body into wheel commands for the base. It also calculates odometry from hardware feedback and shares it.
diff_drive_controller/diff_drive_controller or mecanum_drive_controller/mecanum_drive_controller
ekf_filterThe Extended Kalman Filter node is designed to fuse odometry data from various sources, including wheel encoders, IMU, and GPS.
robot_localization/ekf_filter
gpsNode responsible for parsing NMEA strings and publishing standard ROS NavSat message types.
nmea_navsat_driver/nmea_navsat_driver
gz_bridgeConvert and transmit data between ROS and Gazebo
ros_gz_bridge/parameter_bridge
gz_ros2_controlResponsible for integrating the ros2_control controller architecture with the Gazebo simulator.
gz_ros2_control/gz_ros2_control
gz_estop_guiThe node is part of the Gazebo GUI plugin, enabling easy E-stop state modifications directly within the simulation.
husarion_ugv_gazebo/EStop
hardware_controllerPlugin responsible for communicating with engine controllers via the CAN bus and providing E-Stop functionalities.
husarion_ugv_hardware_interfaces/{robot_model}System
imu_broadcasterPublishes readings of IMU sensors.
imu_sensor_broadcaster/imu_sensor_broadcaster
joint_state_broadcasterReads all state interfaces and reports them on specific topics.
joint_state_broadcaster/joint_state_broadcaster
lights_containerNode for managing ROS components. This node manages: lights_controller, lights_driver.
rclcpp_components/component_container
lights_controllerThis node is responsible for processing animations and publishing frames to light_driver node.
husarion_ugv_lights/LightsControllerNode
lights_driverThis node is responsible for displaying frames on the robot's lights.
husarion_ugv_lights/LightsDriverNode
lights_managerNode responsible for managing lights animation scheduling.
husarion_ugv_manager/lights_manager
⚙️ navsat_transform ⚙️It converts raw GPS data into odometry data and publishes corrected GPS positions based on sensor data at a higher frequency.
robot_localization/navsat_transform
robot_state_publisherBroadcasts a robot's state to tf2 using a provided URDF model and joint states. It updates the model and broadcasts poses for fixed and movable joints to tf2 topics.
robot_state_publisher/robot_state_publisher
safety_managerNode responsible for managing safety features, and software shutdown of components.
husarion_ugv_manager/safety_manager_node
system_monitorPublishes system state of the Built-in Computer such as CPU usage, RAM memory usage, disk usage and CPU temperature.
husarion_ugv_diagnostics/system_monitor_node

Topics

🤖🖥️TopicDescription
battery/battery_statusMean values of both batteries will be published if the robot has two batteries. Otherwise, the state of the single battery will be published.
sensor_msgs/BatteryState
battery/charging_statusBattery charging status value.
husarion_ugv_msgs/ChargingStatus
cmd_velCommand velocity value.
geometry_msgs/Twist
diagnosticsDiagnostic data.
diagnostic_msgs/DiagnosticArray
dynamic_joint_statesInformation about the state of various movable joints in a robotic system.
control_msgs/DynamicJointState
⚙️ gps/filtered ⚙️Filtered GPS position after fusing odometry data.
sensor_msgs/NavSatFix
⚙️ gps/fix ⚙️Raw GPS data.
sensor_msgs/NavSatFix
gps/time_referenceThe timestamp from the GPS device.
sensor_msgs/TimeReference
gps/velVelocity output from the GPS device.
geometry_msgs/TwistStamped
hardware/e_stopCurrent E-stop state.
std_msgs/Bool.
hardware/io_stateCurrent IO state.
husarion_ugv_msgs/IOState
hardware/robot_driver_stateCurrent motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
husarion_ugv_msgs/RobotDriverState
imu/dataFiltered IMU data.
sensor_msgs/Imu
joint_statesProvides information about the state of various joints in a robotic system.
sensor_msgs/JointState
lights/channel_1_frameFrame to be displayed on robot Front Bumper Lights.
sensor_msgs/Image
lights/channel_2_frameFrame to be displayed on robot Rear Bumper Lights.
sensor_msgs/Image
localization/set_poseSets the pose of the EKF node.
geometry_msgs/PoseWithCovarianceStamped
odometry/filteredContains information about the filtered position and orientation. When localization_mode is relative, the position and orientation are relative to the starting point. When localization_mode is enu, the orientation is relative to the east-north-up (ENU) coordinates.
nav_msgs/Odometry
odometry/wheelsRobot odometry calculated from wheels.
nav_msgs/Odometry
robot_descriptionContains information about robot description from URDF file.
std_msgs/String
system_statusState of the system, including Built-in Computer's CPU temperature and load.
husarion_ugv_msgs/SystemStatus
tfTransforms of robot system.
tf2_msgs/TFMessage
tf_staticStatic transforms of robot system.
tf2_msgs/TFMessage

Hidden topics

🤖🖥️TopicDescription
_battery/battery_1_status_rawFirst battery raw state.
sensor_msgs/BatteryState
_battery/battery_2_status_rawSecond battery raw state. Published if second battery detected.
sensor_msgs/BatteryState
_gps/headingNot supported for current configuration.
geometry_msgs/QuaternionStamped
⚙️ _odometry/gps ⚙️Transformed raw GPS data to odometry format.
nav_msgs/Odometry

Services

🤖🖥️ServiceDescription
controller_manager/configure_controllerManage lifecycle transition.
controller_manager_msgs/srv/ConfigureController
controller_manager/list_controller_typesOutput the available controller types and their base classes.
controller_manager_msgs/srv/ListControllerTypes
controller_manager/list_controllersOutput the list of loaded controllers, their type and status.
controller_manager_msgs/srv/ListControllers
controller_manager/list_hardware_componentsOutput the list of available hardware components.
controller_manager_msgs/srv/ListHardwareComponents
controller_manager/list_hardware_interfacesOutput the list of available command and state interfaces.
controller_manager_msgs/srv/ListHardwareInterfaces
controller_manager/load_controllerLoad a controller in a controller manager.
controller_manager_msgs/srv/LoadController
controller_manager/reload_controller_librariesReload controller libraries.
controller_manager_msgs/srv/ReloadControllerLibraries
controller_manager/set_hardware_component_stateAdjust the state of the hardware component.
controller_manager_msgs/srv/SetHardwareComponentState
controller_manager/switch_controllerSwitch controllers in a controller manager.
controller_manager_msgs/srv/SwitchController
controller_manager/unload_controllerUnload a controller in a controller manager.
controller_manager_msgs/srv/UnloadController
hardware/aux_power_enableEnables or disables AUX power.
std_srvs/srv/SetBool
hardware/charger_enableEnables or disables external charger.
std_srvs/srv/SetBool
hardware/digital_power_enableEnables or disables digital power.
std_srvs/srv/SetBool
hardware/e_stop_resetResets E-stop.
std_srvs/srv/Trigger
hardware/e_stop_triggerTriggers E-stop.
std_srvs/srv/Trigger
hardware/fan_enableEnables or disables fan.
std_srvs/srv/SetBool
hardware/motor_torque_enableAllows to enable/disable motor torque when the E-Stop is triggered.
std_srvs/srv/SetBool
lights/set_animationSets LED animation.
husarion_ugv_msgs/srv/SetLEDAnimation
localization/enableEnable EKF node.
std_srvs/srv/Empty
lights/set_brightnessSets global LED brightness, value ranges from 0.0 to 1.0.
husarion_ugv_msgs/SetLEDBrightness
localization/set_poseSet pose of EKF node.
robot_localization/srv/SetPose
localization/toggleToggle filter processing in the EKF node.
robot_localization/srv/ToggleFilterProcessing