Skip to content

Latest commit

 

History

History
127 lines (108 loc) · 31.2 KB

ROS_API.md

File metadata and controls

127 lines (108 loc) · 31.2 KB

ROS API

Important

Beta Release

Please be advised that the software you are about to use is a Beta version of the ROS 2 Driver for 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 Panther ROS 2 driver. You can reach us in the following ways:

ROS 2 System Design

This section describes the ROS packages in the Panther ROS system. These packages are located in the panther_ros GitHub repository.

Note

Differences in ROS System

ROS 2 nodes differs slightly between Panther v1.06 and Panther v1.2+. This is caused by internal 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 Panther's hardware 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/panther_ros. These packages are responsible for accessing the hardware components of the robot.

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

Panther ROS 2 API 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.

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

Nodes

Node name Description
🤖 battery_driver Publishes battery state read from ADC unit for Panther version 1.2 and above, or based on Roboteq motor controllers' data for earlier versions of the robot.
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
🤖 hardware_controller Plugin responsible for communicating with engine controllers via the CAN bus and providing E-Stop functionalities.
panther_hardware_interfaces/PantherSystem
🤖 gps Node responsible for parsing NMEA strings and publishing standard ROS NavSat message types.
nmea_navsat_driver/nmea_navsat_driver
🖥️ 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.
panther_gazebo/EStop
🤖🖥️ 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 be displayed on the Husarion Panther robot Bumper Lights.
panther_lights/LightsControllerNode
🤖 lights_driver This node is responsible for displaying frames on the Husarion Panther robot's Bumper Lights.
panther_lights/LightsDriverNode
🤖🖥️ lights_manager Node responsible for managing Bumper Lights animation scheduling.
panther_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
🖥️ panther_base_gz_bridge Convert and transmit data between ROS and Gazebo
ros_gz_bridge/parameter_bridge
🤖🖥️ 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.
panther_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.
panther_diagnostic/system_monitor_node

Topics

Topic Description
🤖🖥️ battery/battery_status Mean values of both batteries if Panther has two batteries. Otherwise, the state of the single battery will be published.
sensor_msgs/BatteryState
🤖 battery/charging_status Battery charging status value.
panther_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.
panther_msgs/IOState
🤖🖥️ hardware/motor_controllers_state Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
panther_msgs/DriverState
🤖🖥️ 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.
panther_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

Services

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_power_enable Enables or disables motor power.
std_srvs/srv/SetBool
🤖🖥️ lights/set_animation Sets LED animation.
panther_msgs/srv/SetLEDAnimation
🤖 lights/set_brightness Sets global LED brightness, value ranges from 0.0 to 1.0.
panther_msgs/SetLEDBrightness
🤖🖥️ localization/enable Enable EKF node.
std_srvs/srv/Empty
🤖🖥️ 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