Skip to main content

ROS API

Overview

Robot Operating System (ROS) is a set of software libraries and tools that help build robot applications. It provides a common framework for developing robot software, making it easier to share code and ideas between developers. ROS is also open-source, which means that it is free to use and modify.

By default, the Panther ROS system is deployed using Docker. Docker is a containerization platform that makes it easy to deploy and manage software. It also simplifies the process of updating the Panther ROS system.

The provided Panther ROS system is designed to compose all the basic functionalities of the robot. It allows to control of the robot with velocity commands and provides the user with odometry information, which can be used for robot localization. The Panther ROS system is also designed to monitor the robot's state and perform safety features that will prevent any hazardous behavior. The basic states of the robot are represented by the Bumper Lights signals. This allows the user to recognize if the robot is ready to operate or in E-stop mode, informs about the Battery state, or displays an animation indicating the occurrence of an error in the system. More detailed information about the state of the robot can be acquired using ROS topics. Errors in the system are also logged into the system and can be easily accessed using the Docker interface. The Panther ROS system includes a robot description, which can be used to visualize the robot with all its components.

The Panther ROS system is designed to be easy to use and maintain. It is also designed to be extensible so that it can be easily customized for different applications.

Running ROS Node Natively

Our default configuration is shipped within a Docker container, but this doesn't mean you can't run Panther ROS drivers without it. You can find all the instructions on how to build them on panther_ros GitHub page.

AUTOSTART NATIVE ROS DRIVER

Natively build ROS packages will miss autostart functionality. It is up to the user to add it. You can do so for example by creating systemd.service.

ROS System Design

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

DIFFERENCES IN ROS SYSTEM

ROS nodes differs between Panther v1.0 - v1.06 and Panther v1.2 - 1.21. 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.

This diagram represents the Panther ROS system. Some topics and services have been excluded from the graph for the sake of clarity.

ROS API

panther_battery

Package containing nodes monitoring and publishing the internal Battery state of the Husarion Panther robot.

Pulled from: panther_battery/README.md

adc_node.py

Publishes Battery state read from ADC unit and thermistors. Voltage, current, and temperature are smoothed out using a moving average.

Subscribers

  • /panther/driver/motor_controllers_state [panther_msgs/DriverState]: current motor controllers' state and error flags.
  • /panther/hardware/io_state [panther_msgs/IOState]: checks if charger is connected. Later fuses the information with the charging current.

Publishers

  • /panther/battery [sensor_msgs/BatteryState]: average values of both batteries if the panther has two batteries. In the case of single Battery values only for the single one.
  • /panther/battery_1 [sensor_msgs/BatteryState]: first Battery state. Published if second Battery detected.
  • /panther/battery_2 [sensor_msgs/BatteryState]: second Battery state. Published if second Battery detected.

panther_bringup

The package contains the default configuration and launch files necessary to start all the basic functionalities of the Husarion Panther robot.

Pulled from: panther_bringup/README.md

welcome_msg_node.py

Displays user-friendly welcome message:

 ____             _   _               
| _ \ __ _ _ __ | |_| |__ ___ _ __
| |_) / _` | '_ \| __| '_ \ / _ \ '__|
| __/ (_| | | | | |_| | | | __/ |
|_| \__,_|_| |_|\__|_| |_|\___|_|

Serial number: ----
Robot version: 1.0
ROS driver version: 1.1.0
Website: https://husarion.com
Support: https://community.husarion.com/
Bugtracker: https://github.com/husarion/panther_ros/issues

Parameters

  • ~exit_on_wrong_hw [bool, default: true]: if set to true stops the node if incorrect hardware is detected. Otherwise, keeps spinning the node.
  • /panther/serial_no [string, default: ----]: serial number of a robot.
  • /panther/robot_version [string, default: 1.0]: robot hardware revision.

External ROS Nodes

Pulled from: panther_bringup/README.md

ekf_localization_node.cpp

External node type: robot_localization/ekf_localization_node.

Extended Kalman Filter node for more accurate odometry. For more information, refer to robot_localization. The default configuration is stored in panther_bringup/ekf_config.yaml.

Subscribers

  • /panther/odom/wheels [nav_msgs/Odometry]: robot odometry calculated from wheels.
  • /panther/imu/data [panther_msgs/IOState]: filtered IMU data.
  • /tf [tf2_msgs/TFMessage]: transforms of robot system.

Publishers

  • /panther/odom/filtered [nav_msgs/Odometry]: provides filtered odometry information. This topic contains a fused and enhanced estimate of the robot's pose and velocity, incorporating data from various sensors and correcting for any errors in the estimated state.
  • /tf [tf2_msgs/TFMessage]: publishes base_link to odom transform.

Service Servers

  • /panther/set_pose [robot_localization/SetPose]: by issuing a geometry_msgs/PoseWithCovarianceStamped message to the set_pose topic, users can manually set the state of the filter. This is useful for resetting the filter during testing and allows for interaction with RViz. Alternatively, the state estimation nodes advertise a SetPose service, whose type is robot_localization/SetPose.

imu_filter_node.cpp

External node type: imu_filter_madgwick/imu_filter_node.

Node responsible for filtering and fusing raw data from the IMU.

Subscribers

  • /panther/imu/data_raw [sensor_msgs/Imu]: the raw accelerometer and gyroscope data.

Publishers

  • /panther/imu/data [sensor_msgs/Imu]: the fused IMU messages, containing the orientation.

phidgets_spatial_node.cpp

External node type: phidgets_spatial/phidgets_spatial_nodelet.cpp.

The ROS driver for Phidgets Spatial.

Publishers

  • /panther/imu/data_raw [sensor_msgs/Imu]: the raw accelerometer and gyroscope data.
  • /panther/imu/is_calibrated [std_msgs/Bool]: whether the gyroscope has been calibrated. This will be done automatically at startup time but can also be re-done at any time by calling the imu/calibrate service.
  • /panther/imu/mag [sensor_msgs/MagneticField]: the raw magnetometer data.

Service Servers

  • /panther/imu/calibrate [std_srvs/Empty]: run calibration on the gyroscope.

panther_driver

Software for controlling the Husarion Panther robot motors via CAN interface.

Pulled from: panther_driver/README.md

driver_node.py

Node responsible for communication with motor controllers and computing inverse and forward kinematics of a robot. Commanded velocities are smoothed with acceleration constraints.

Subscribers

  • /cmd_vel [geometry_msgs/Twist]: robot desired control velocity.
  • /panther/hardware/e_stop [std_msgs/Bool]: robot E-stop state.
  • /panther/hardware/io_state [panther_msgs/IOState]: checks whether robot GPIO pins are powered on.

Publishers

  • /joint_states [sensor_msgs/JointState]: robot joints states.
  • /panther/driver/motor_controllers_state [panther_msgs/DriverState]: motor controllers current, voltage, fault flags, script flags and runtime error flags. If the robot's motors are disabled, no messages will be sent to this topic.
  • /panther/odom/wheels [nav_msgs/Odometry]: robot odometry calculated from wheels.
  • /panther/pose [geometry_msgs/Pose]: robot position.
  • /tf [tf2_msgs/TFMessage]: transform between odom and base_link frames.

For a /joint_states topic, message carries given data:

  • position = [fl_wheel_joint, fr_wheel_joint, rl_wheel_joint, rr_wheel_joint] wheel position in [rad], ranging from [-pi, pi].
  • velocity = [fl_wheel_joint, fr_wheel_joint, rl_wheel_joint, rr_wheel_joint] wheels velocity in [rad/s].
  • effort = [fl_wheel_joint, fr_wheel_joint, rl_wheel_joint, rr_wheel_joint] Approximate motor torque in [Nm].

Service Servers

  • /panther/driver/reset_roboteq_script [std_srvs/Trigger]: resets the script running on motor drivers. Available since Panther version 1.2.

Service Clients

  • /panther/hardware/e_stop_trigger [std_srvs/Trigger]: allows to trigger robot E-stop.

Parameters

  • ~base_link_frame [string, default: base_link]: the name of the base_link frame.
  • ~can_interface [string, default: panther_can]: the name of the socket CAN interface.
  • ~eds_file [string, default: None]: required path to eds file containing CANopen configuration for the Roboteq motor controllers.
  • ~encoder_resolution [int, default: 1600]: resolution of motor encoder in [PPR].
  • ~gear_ratio [float, default: 30.08]: wheel gear ratio.
  • ~kinematics [string, default: differential]: kinematics type, possible are differential and mecanum.
  • ~motor_torque_constant [float, default: 2.6149]: constant used to estimate torque.
  • ~odom_frame [string, default: odom]: the name of the odom frame.
  • ~odom_stderr/vel_x [float, default: 3.2e-3]: standard error used to place in covariance matrix, after squaring, in odometry message.
  • ~odom_stderr/vel_y [float, default: 3.2e-3]: standard error used to place in covariance matrix, after squaring, in odometry message.
  • ~odom_stderr/vel_yaw [float, default: 8.5e-3]: standard error used to place in covariance matrix, after squaring, in odometry message.
  • ~publish_joints [bool, default: true]: whether to publish robot joints_states.
  • ~publish_odometry [bool, default: true]: whether to publish robot odometry.
  • ~publish_pose [bool, default: true]: whether to publish robot pose.
  • ~publish_tf [bool, default: true]: whether to publish transform between odom and base_link frames.
  • ~robot_length [float, default: 0.44]: distance between wheels alongside X axis in [m].
  • ~use_pdo [bool, default: false]: whether to use Process Data Object protocol to acquire motors drivers data via CAN interface. Available since Panther version 1.2.
  • ~wheel_radius [float, default: 0.1825]: wheel radius in [m].
  • ~wheel_separation [float, default: 0.697]: separation of wheels alongside Y axis in [m].
  • velocity_x_stderr [float, default: 3.2e-3]: standard error used to place in covariance matrix, after squaring, in odometry message.
  • velocity_y_stderr [float, default: 3.2e-3]: standard error used to place in covariance matrix, after squaring, in odometry message.
  • velocity_yaw_stderr [float, default: 8.5e-3]: standard error used to place in covariance matrix, after squaring, in odometry message.

  • ~max_vel_x [float, default: 2.0]: maximum linear vlelocity in X direction.
  • ~max_vel_y [float, default: 2.0]: maximum linear vlelocity in Y direction.
  • ~max_vel_theta [float, default: 4.0]: maximum angular velocity.
  • ~acc_lim_x [float, default: 1.0]: maximum linear acceleration in X direction.
  • ~acc_lim_y [float, default: 1.0]: maximum linear acceleration in Y direction.
  • ~acc_lim_theta [float, default: 1.57]: maximum angular acceleration.
  • ~decel_lim_x [float, default: 1.5]: maximum linear decelaration in X direction.
  • ~decel_lim_y [float, default: 1.5]: maximum linear decelaration in Y direction.
  • ~decel_lim_theta [float, default: 2.3]: maximum angular deceleration.
  • ~emergency_decel_lim_x [float, default: 2.7]: maximum linear decelaration in X direction when a timeout is reached for velocity commands.
  • ~emergency_decel_lim_y [float, default: 2.7]: maximum linear decelaration in Y direction when a timeout is reached for velocity commands.
  • ~emergency_decel_lim_theta [float, default: 5.74]: maximum angular deceleration when a timeout is reached for velocity commands.

panther_lights

Package used to control the Husarion Panther Bumper Lights.

Pulled from: panther_lights/README.md

controller_node.py

This node is responsible for processing animations and publishing frames to be displayed on the Husarion Panther robot Bumper Lights.

Publishers

  • /panther/lights/driver/front_panel_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: an animation frame pixels to be displayed on robot Front Bumper Lights.
  • /panther/lights/driver/rear_panel_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: an animation frame pixels to be displayed on robot Rear Bumper Lights.
  • /panther/lights/controller/queue [panther_msgs/LEDAnimationQueue]: list of names of currently enqueued animations in the controller node, the first element of the list is the currently displayed animation.

Service Servers

  • /panther/lights/controller/set/animation [panther_msgs/SetLEDAnimation]: allows setting animation on Bumper Lights based on animation ID.
  • /panther/lights/controller/set/image_animation [panther_msgs/SetLEDImageAnimation]: allows setting animation based on provided images. Only available if ~test parameter is set to true.
  • /panther/lights/controller/update_animations [std_srvs/Trigger]: allows updating user-defined animations using ~user_animations parameter.

Parameters

  • ~animations [list, default: None]: required list of defined animations.
  • ~controller_frequency [float, default: 46.0]: frequency [Hz] at which the lights controller node will process animations.
  • ~num_led [int, default: 46]: number of LEDs in a single bumper. Must match driver num_led in driver_node.
  • ~test [bool, default: false]: enables /panther/lights/controller/set/image_animation service.
  • ~user_animations [list, default: None]: optional list of animations defined by the user.

driver_node

This node is responsible for displaying frames on the Husarion Panther robot's Bumper Lights.

Subscribers

  • /panther/lights/driver/front_panel_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: an animation frame to be displayed on robot Front Bumper Lights.
  • /panther/lights/driver/rear_panel_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: an animation frame to be displayed on robot Rear Bumper Lights.

Service Servers

  • /panther/lights/driver/set/brightness [panther_msgs/SetLEDBrightness]: allows setting global LED brightness, value ranges from 0.0 to 1.0.

Parameters

  • ~frame_timeout [float, default: 0.1]: time in [s] after which an incoming frame will be considered too old.
  • ~global_brightness [float, default: 1.0]: LED global brightness. The range between [0.0, 1.0].
  • ~num_led [int, default: 46]: number of LEDs in a single bumper.

panther_manager

A package containing nodes responsible for high-level control of Husarion Panther robot.

Pulled from: panther_manager/README.md

manager_bt_node

Node responsible for managing the Husarion Panther robot. Composes control of three behavior trees responsible for handling Bumper Lights animation scheduling, safety features, and software shutdown of components.

Subscribers

  • /panther/battery [sensor_msgs/BatteryState]: state of the internal Battery.
  • /panther/driver/motor_controllers_state [panther_msgs/DriverState]: state of motor controllers.
  • /panther/hardware/e_stop [std_msgs/Bool]: state of emergency stop.
  • /panther/hardware/io_state [panther_msgs/IOState]: state of IO pins.
  • /panther/system_status [panther_msgs/SystemStatus]: state of the system, including Built-in Computer's CPU temperature and load.

Service Clients

  • /panther/hardware/aux_power_enable [std_srvs/SetBool]: enables Aux Power output.
  • /panther/hardware/e_stop_trigger [std_srvs/Trigger]: triggers E-stop.
  • /panther/hardware/fan_enable [std_srvs/SetBool]: enables fan.
  • /panther/lights/controller/set/animation [panther_msgs/SetLEDAnimation]: allows setting animation on Bumper Lights based on animation ID.

Parameters

  • ~battery_percent_window_len [int, default: 6]: moving average window length used to smooth out Battery percentage readings.
  • ~battery_temp_window_len [int, default: 6]: moving average window length used to smooth out temperature readings of the Battery.
  • ~bt_project_file [string, default: $(find panther_manager)/config/PantherBT.btproj]: path to a BehaviorTree project.
  • ~cpu_temp_window_len [int, default: 6]: moving average window length used to smooth out temperature readings of the Built-in Computer's CPU.
  • ~driver_temp_window_len [int, default: 6]: moving average window length used to smooth out the temperature readings of each driver.
  • ~launch_lights_tree [bool, default: true]: launch behavior tree responsible for scheduling animations on Panther Bumper Lights.
  • ~launch_safety_tree [bool, default: true]: launch behavior tree responsible for managing Panther safety measures.
  • ~launch_shutdown_tree [bool, default: true]: launch behavior tree responsible for the gentle shutdown of robot components.
  • ~lights/battery_state_anim_period [float, default: 120.0]: time in [s] to wait before repeating animation representing the current Battery percentage.
  • ~lights/critical_battery_anim_period [float, default: 15.0]: time in [s] to wait before repeating animation, indicating a critical Battery state.
  • ~lights/critical_battery_threshold_percent [float, default: 0.1]: if the Battery percentage drops below this value, an animation indicating a critical Battery state will start being displayed.
  • ~lights/low_battery_anim_period [float, default: 30.0]: time in [s] to wait before repeating the animation, indicating a low Battery state.
  • ~lights/low_battery_threshold_percent [float, default: 0.4]: if the Battery percentage drops below this value, the animation indicating a low Battery state will start being displayed.
  • ~lights/update_charging_anim_step [float, default: 0.1]: percentage representing how discretized the Battery state animation should be.
  • ~plugin_libs [list, default: Empty list]: list with names of plugins that are used in the BT project.
  • ~ros_plugin_libs [list, default: Empty list]: list with names of ROS plugins that are used in a BT project.
  • ~safety/cpu_fan_off_temp [float, default: 60.0]: temperature in C] of the Built-in Computer's CPU, below which the fan is turned off.
  • ~safety/cpu_fan_on_temp [float, default: 70.0]: temperature in C] of the Built-in Computer's CPU, above which the fan is turned on.
  • ~safety/driver_fan_off_temp [float, default: 35.0]: temperature in C] of any drivers below which the fan is turned off.
  • ~safety/driver_fan_on_temp [float, default: 45.0]: temperature in C] of any drivers above which the fan is turned on.
  • ~shutdown_hosts_file [string, default: None]: path to a YAML file containing a list of hosts to request shutdown. To correctly format the YAML file, include a hosts field consisting of a list with the following fields:
    • command [string, default: sudo shutdown now]: command executed on shutdown of given device.
    • ip [string, default: None]: IP of a host to shutdown over SSH.
    • ping_for_success [bool, default: true]: ping host until it is not available or timeout is reached.
    • port [string, default: 22]: SSH communication port.
    • timeout [string, default: 5.0]: time in [s] to wait for the host to shutdown. The Built-in Computer will turn off after all computers are shutdown or reached timeout. Keep in mind that hardware will cut power off after a given time after pressing the power button. Refer to the hardware manual for more information.
    • username [string, default: None]: username used to log in to over SSH.

system_status_node.py

Publishes stats and status of the Built-in Computer. Stats include CPU utilization and temperature, as well as disk and RAM usage.

Publishers

  • /panther/system_status [panther_msgs/SystemStatus]: information about Built-in Computer CPU temperature, utilization, disk, and RAM usage.

panther_power_control

A package containing nodes responsible for power management of the Husarion Panther robot.

Pulled from: panther_power_control/README.md

power_board_node.py

Node responsible for management of the Safety Board and the Power Board.

Subscribers

  • /cmd_vel [geometry_msgs/Twist]: observes if velocity commands are sent to the robot. Prevents disabling E-stop if published.
  • /panther/driver/motor_controllers_state [panther_msgs/DriverState]: checks for errors on motor controllers.

Publishers

  • /panther/hardware/e_stop [std_msgs/Bool, latched: true]: the current state of the E-stop.
  • /panther/hardware/io_state [panther_msgs/IOState, latched: true]: publishes state of panther IO pins. Message fields are related to:
    • aux_power: related to service aux_power_enable,
    • charger_connected: indicates if standard charger is connected,
    • charger_enabled: related to service charger_enable,
    • digital_power: related to service digital_power_enable,
    • fan: related to service fan_enable,
    • motor_power: related to service motor_power_enable,
    • power_button: indicates if the Power Button is pressed.

Service Servers

  • /panther/hardware/aux_power_enable [std_srvs/SetBool]: enable or disable AUX Power output, e.g., supply to robotic arms.
  • /panther/hardware/charger_enable [std_srvs/SetBool]: if a non-standard charger is available, this service allows enabling and disabling it.
  • /panther/hardware/digital_power_enable [std_srvs/SetBool]: enable or disable the internal digital power used to power on, e.g. User Computer, Router, etc.
  • /panther/hardware/e_stop_reset [std_srvs/Trigger]: reset E-stop.
  • /panther/hardware/e_stop_trigger [std_srvs/Trigger]: trigger E-stop.
  • /panther/hardware/fan_enable [std_srvs/SetBool]: enable or disable the internal fan. Calling the service from the terminal when it is enabled might yield unintuitive behavior. This is because manager_node overwrites control. It is advisable to use manager_node when implementing fan behaviors.
  • /panther/hardware/motor_power_enable [std_srvs/SetBool]: enable or disable motor drivers.

Service Clients

  • /panther/driver/reset_roboteq_script [std_srvs/Trigger]: used to reset the Roboteq drivers script when enabling motor drivers.