Important
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:
- By email at: [email protected]
- Via our community forum: Husarion Community
- By submitting an issue request on: GitHub
This section describes the ROS packages used in Husarion UGV. These packages are located in the husarion_ugv_ros GitHub repository.
Note
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.
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.
Symbol | Meaning |
---|---|
🤖 | Available for physical robot |
🖥️ | Available in simulation |
⚙️ | Requires specific configuration |
🤖 | 🖥️ | Node name | Description |
---|---|---|---|
✅ | ❌ | battery_driver |
Publishes battery state read from ADC unit. panther_batter/battery_driver_node |
✅ | ✅ | controller_manager |
The 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_controller |
Manages 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_filter |
The Extended Kalman Filter node is designed to fuse odometry data from various sources, including wheel encoders, IMU, and GPS. robot_localization/ekf_filter |
✅ | ❌ | gps |
Node responsible for parsing NMEA strings and publishing standard ROS NavSat message types. nmea_navsat_driver/nmea_navsat_driver |
❌ | ✅ | gz_bridge |
Convert and transmit data between ROS and Gazebo ros_gz_bridge/parameter_bridge |
❌ | ✅ | gz_ros2_control |
Responsible for integrating the ros2_control controller architecture with the Gazebo simulator. gz_ros2_control/gz_ros2_control |
❌ | ✅ | gz_estop_gui |
The node is part of the Gazebo GUI plugin, enabling easy E-stop state modifications directly within the simulation. husarion_ugv_gazebo/EStop |
✅ | ❌ | hardware_controller |
Plugin responsible for communicating with engine controllers via the CAN bus and providing E-Stop functionalities. husarion_ugv_hardware_interfaces/{robot_model}System |
✅ | ✅ | imu_broadcaster |
Publishes readings of IMU sensors. imu_sensor_broadcaster/imu_sensor_broadcaster |
✅ | ✅ | joint_state_broadcaster |
Reads all state interfaces and reports them on specific topics. joint_state_broadcaster/joint_state_broadcaster |
✅ | ✅ | lights_container |
Node for managing ROS components. This node manages: lights_controller , lights_driver . rclcpp_components/component_container |
✅ | ✅ | lights_controller |
This node is responsible for processing animations and publishing frames to light_driver node. husarion_ugv_lights/LightsControllerNode |
✅ | ❌ | lights_driver |
This node is responsible for displaying frames on the robot's lights. husarion_ugv_lights/LightsDriverNode |
✅ | ✅ | lights_manager |
Node 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_publisher |
Broadcasts 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_manager |
Node responsible for managing safety features, and software shutdown of components. husarion_ugv_manager/safety_manager_node |
✅ | ❌ | system_monitor |
Publishes 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 |
🤖 | 🖥️ | Topic | Description |
---|---|---|---|
✅ | ✅ | battery/battery_status |
Mean 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_status |
Battery charging status value. husarion_ugv_msgs/ChargingStatus |
✅ | ✅ | cmd_vel |
Command velocity value. geometry_msgs/Twist |
✅ | ✅ | diagnostics |
Diagnostic data. diagnostic_msgs/DiagnosticArray |
✅ | ✅ | dynamic_joint_states |
Information 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_reference |
The timestamp from the GPS device. sensor_msgs/TimeReference |
✅ | ❌ | gps/vel |
Velocity output from the GPS device. geometry_msgs/TwistStamped |
✅ | ✅ | hardware/e_stop |
Current E-stop state. std_msgs/Bool. |
✅ | ❌ | hardware/io_state |
Current IO state. husarion_ugv_msgs/IOState |
✅ | ✅ | hardware/robot_driver_state |
Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data. husarion_ugv_msgs/RobotDriverState |
✅ | ✅ | imu/data |
Filtered IMU data. sensor_msgs/Imu |
✅ | ✅ | joint_states |
Provides information about the state of various joints in a robotic system. sensor_msgs/JointState |
✅ | ✅ | lights/channel_1_frame |
Frame to be displayed on robot Front Bumper Lights. sensor_msgs/Image |
✅ | ✅ | lights/channel_2_frame |
Frame to be displayed on robot Rear Bumper Lights. sensor_msgs/Image |
✅ | ✅ | localization/set_pose |
Sets the pose of the EKF node. geometry_msgs/PoseWithCovarianceStamped |
✅ | ✅ | odometry/filtered |
Contains 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/wheels |
Robot odometry calculated from wheels. nav_msgs/Odometry |
✅ | ✅ | robot_description |
Contains information about robot description from URDF file. std_msgs/String |
✅ | ❌ | system_status |
State of the system, including Built-in Computer's CPU temperature and load. husarion_ugv_msgs/SystemStatus |
✅ | ✅ | tf |
Transforms of robot system. tf2_msgs/TFMessage |
✅ | ✅ | tf_static |
Static transforms of robot system. tf2_msgs/TFMessage |
Hidden topics
🤖 | 🖥️ | Topic | Description |
---|---|---|---|
✅ | ❌ | _battery/battery_1_status_raw |
First battery raw state. sensor_msgs/BatteryState |
✅ | ❌ | _battery/battery_2_status_raw |
Second battery raw state. Published if second battery detected. sensor_msgs/BatteryState |
✅ | ❌ | _gps/heading |
Not supported for current configuration. geometry_msgs/QuaternionStamped |
✅ | ✅ | ⚙️ _odometry/gps ⚙️ |
Transformed raw GPS data to odometry format. nav_msgs/Odometry |
🤖 | 🖥️ | Service | Description |
---|---|---|---|
✅ | ✅ | controller_manager/configure_controller |
Manage lifecycle transition. controller_manager_msgs/srv/ConfigureController |
✅ | ✅ | controller_manager/list_controller_types |
Output the available controller types and their base classes. controller_manager_msgs/srv/ListControllerTypes |
✅ | ✅ | controller_manager/list_controllers |
Output the list of loaded controllers, their type and status. controller_manager_msgs/srv/ListControllers |
✅ | ✅ | controller_manager/list_hardware_components |
Output the list of available hardware components. controller_manager_msgs/srv/ListHardwareComponents |
✅ | ✅ | controller_manager/list_hardware_interfaces |
Output the list of available command and state interfaces. controller_manager_msgs/srv/ListHardwareInterfaces |
✅ | ✅ | controller_manager/load_controller |
Load a controller in a controller manager. controller_manager_msgs/srv/LoadController |
✅ | ✅ | controller_manager/reload_controller_libraries |
Reload controller libraries. controller_manager_msgs/srv/ReloadControllerLibraries |
✅ | ✅ | controller_manager/set_hardware_component_state |
Adjust the state of the hardware component. controller_manager_msgs/srv/SetHardwareComponentState |
✅ | ✅ | controller_manager/switch_controller |
Switch controllers in a controller manager. controller_manager_msgs/srv/SwitchController |
✅ | ✅ | controller_manager/unload_controller |
Unload a controller in a controller manager. controller_manager_msgs/srv/UnloadController |
✅ | ❌ | hardware/aux_power_enable |
Enables or disables AUX power. std_srvs/srv/SetBool |
✅ | ❌ | hardware/charger_enable |
Enables or disables external charger. std_srvs/srv/SetBool |
✅ | ❌ | hardware/digital_power_enable |
Enables or disables digital power. std_srvs/srv/SetBool |
✅ | ✅ | hardware/e_stop_reset |
Resets E-stop. std_srvs/srv/Trigger |
✅ | ✅ | hardware/e_stop_trigger |
Triggers E-stop. std_srvs/srv/Trigger |
✅ | ❌ | hardware/fan_enable |
Enables or disables fan. std_srvs/srv/SetBool |
✅ | ❌ | hardware/motor_torque_enable |
Allows to enable/disable motor torque when the E-Stop is triggered. std_srvs/srv/SetBool |
✅ | ✅ | lights/set_animation |
Sets LED animation. husarion_ugv_msgs/srv/SetLEDAnimation |
✅ | ✅ | localization/enable |
Enable EKF node. std_srvs/srv/Empty |
✅ | ❌ | lights/set_brightness |
Sets global LED brightness, value ranges from 0.0 to 1.0. husarion_ugv_msgs/SetLEDBrightness |
✅ | ✅ | localization/set_pose |
Set pose of EKF node. robot_localization/srv/SetPose |
✅ | ✅ | localization/toggle |
Toggle filter processing in the EKF node. robot_localization/srv/ToggleFilterProcessing |