Skip to main content

ROS 2 Packages Overview

panther_battery

The package containing nodes monitoring and publishing the internal battery state of the Husarion Panther robot.

Launch Files

This package contains:

  • battery.launch.py: Responsible for activating battery node, which dealing with reading and publishing battery data.

ROS Nodes

battery_driver_node

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.

Publishes
  • _battery/battery_1_status_raw [sensor_msgs/BatteryState]: First battery raw state.
  • _battery/battery_2_status_raw [sensor_msgs/BatteryState]: Second battery raw state. Published if second battery detected.
  • battery/battery_status [sensor_msgs/BatteryState]: Mean values of both batteries if Panther has two batteries. Otherwise, the state of the single battery will be published.
  • battery/charging_status [panther_msgs/ChargingStatus]: Battery charging status.
  • diagnostics [diagnostic_msgs/DiagnosticArray]: Battery diagnostic messages.
Subscribers
  • hardware/io_state [panther_msgs/IOState]: Current state of IO.
  • hardware/motor_controllers_state [panther_msgs/DriverState]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
Parameters
  • ~/adc/device0 [string, default: /sys/bus/iio/devices/iio:device0]: ADC nr 0 IIO device. Used with Panther version 1.2 and above.
  • ~/adc/device1 [string, default: /sys/bus/iio/devices/iio:device1]: ADC nr 1 IIO device. Used with Panther version 1.2 and above.
  • ~/adc/ma_window_len/charge [int, default: 10]: Window length of a moving average, used to smooth out battery charge readings. Used with Panther version 1.2 and above.
  • ~/adc/ma_window_len/temp [int, default: 10]: Window length of a moving average, used to smooth out battery temperature readings. Used with Panther version 1.2 and above.
  • ~/battery_timeout [float, default: 1.0]: Specifies the timeout in seconds. If the node fails to read battery data exceeding this duration, the node will publish an unknown battery state.
  • ~/ma_window_len/voltage [int, default: 10]: Window length of a moving average, used to smooth out battery voltage readings.
  • ~/ma_window_len/current [int, default: 10]: Window length of a moving average, used to smooth out battery current readings.
  • ~/roboteq/driver_state_timeout [float, default: 0.2]: Specifies timeout in seconds after which driver state messages will be considered old. Used with Panther version 1.06 and earlier.

panther_bringup

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

Launch Files

This package contains:

  • bringup.launch.py: Responsible for activating whole robot system.

panther_controller

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

Launch Files

  • controller.launch.py: Establishes communication with the hardware by loading the robot's URDF with plugins and configures the controllers to exchange information between the engine driver and the IMU.

Configuration Files

  • WH01_controller.yaml: Configures imu_broadcaster, joint_state_broadcaster and drive_controller controllers for default WH01 wheels.
  • WH02_controller.yaml: Configures imu_broadcaster, joint_state_broadcaster and drive_controller controllers for mecanum WH02 wheels.
  • WH04_controller.yaml: Configures imu_broadcaster, joint_state_broadcaster and drive_controller controllers for small pneumatic WH04 wheels.

panther_description

The package contains URDF files responsible for creating a representation of the robot by specifying the relationships and types of connections (joints) between individual links. It also contains information about the robot's mesh.

Launch Files

  • load_urdf.launch.py - loads the robot's URDF and creates simple bindings to display moving joints.

Configuration Files

  • components.yaml: Allows you to quickly add visualization of sensors, TF connections and simulate their behavior in the simulator.
  • WH01.yaml: Description of physical and visual parameters for the wheel WH01.
  • WH02.yaml: Description of physical and visual parameters for the wheel WH02.
  • WH04.yaml: Description of physical and visual parameters for the wheel WH04.

panther_diagnostics

Package containing nodes monitoring and publishing the Built-in Computer status of Husarion Panther robot.

Launch Files

  • system_monitor.launch.py: Launch a node that analyzes the state of the most important components in the robot

Configuration Files

ROS Nodes

system_monitor_node

Publishes the built-in computer system status , monitoring parameters as such as CPU usage, RAM usage, disk usage, and CPU temperature.

Publishes
  • diagnostics [diagnostic_msgs/DiagnosticArray]: System monitor diagnostic messages.
  • system_status [panther_msgs/SystemStatus]: Built-in computer system status, includes the most important computation-related parameters.
Parameters
  • ~cpu_usage_warn_threshold [float, default: 95.0]: Threshold for CPU usage warning in percentage.
  • ~cpu_temperature_warn_threshold [float, default: 80.0]: Threshold for CPU temperature warning in degrees Celsius.
  • ~ram_usage_warn_threshold [float, default: 95.0]: Threshold for memory usage warning in percentage.
  • ~disk_usage_warn_threshold [float, default: 95.0]: Threshold for disk usage warning in percentage.
  • ~publish_frequency [double, default: 5.0]: System status publishing frequency [Hz].

panther_gazebo

The package contains a launch file and source files used to run the robot simulation in Gazebo. The simulator tries to reproduce the behavior of a real robot as much as possible, including the provision of an analogous ROS_API.

Launch Files

  • spawn_robot.launch.py: Responsible for spawning the robot in the simulator.
  • simulate_robot.launch.py: Responsible for giving birth to the robot and simulating its physical behavior, such as driving, displaying data, etc.
  • simulate_multiple_robots.launch.py: Similar to the above with logic allowing you to quickly add a swarm of robots.
  • simulation.launch.py: A target file that runs the gazebo simulator that adds and simulates the robot's behavior in accordance with the given arguments.

Configuration Files

ROS Nodes

EStop

EStop is a Gazebo GUI plugin responsible for easy and convenient changing of the robot's E-stop state.

Service Clients
  • hardware/e_stop_reset [std_srvs/Trigger]: Resets E-stop.
  • hardware/e_stop_trigger [std_srvs/Trigger]: Triggers E-stop.

GzPantherSystem

Plugin based on ign_system is responsible for handling sensor interfaces (only IMU for now) and sending requests for joints compatible with ros2_control. Plugin also adds E-Stop support.

Publishers
  • gz_ros2_control/e_stop [std_msgs/Bool]: Current E-stop state.
Service Servers
  • gz_ros2_control/e_stop_reset [std_srvs/Trigger]: Resets E-stop.
  • gz_ros2_control/e_stop_trigger [std_srvs/Trigger]: Triggers E-stop.
note

Above topics and services should be remapped to match real robot

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro).

  • e_stop_initial_state [bool, default: true]: Initial state of E-stop.

LEDStrip

LEDStrip is a Gazebo System plugin responsible for visualizing light and displaying markers based on the data received from a gz::msgs::Image message.

note

The topics and services mentioned below are related to Gazebo interfaces, not ROS interfaces.

Subscribers
  • {topic} [gz::msgs::Image]: Subscribes to an image message for visualization. The topic is specified via a parameter.
Service Servers
  • /marker [gz::msgs::Marker]: Service to request markers for visualizing the received image.
Parameters

The following parameters are required when including this interface in the URDF (you can refer to the gazebo.urdf.xacro file for details).

  • light_name [string, default: ""]: The name of the light entity. The visualization will be attached to this entity.
  • topic [string, default: ""]: The name of the topic from which the Image message is received.
  • namespace [string, default: ""]: Specifies the namespace to differentiate topics and models in scenarios with multiple robots.
  • frequency [double, default: 10.0]: Defines the frequency at which the animation is updated.
  • width [double, default: 1.0]: Specifies the width (y-axis) of the visualization array.
  • height [double, default: 1.0]: Specifies the height (z-axis) of the visualization array.

panther_hardware_interfaces

Package that implements SystemInterface from ros2_control for Panther.

ROS Nodes

This package doesn't contain any standalone nodes, only plugins that are loaded by the resource manager. To use this hardware interface, add it to your URDF. You can check how to do it in panther_description.

PantherSystem

Plugin responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionalities and managing Built-in Computer GPIO ports.

Publishers
  • diagnostics [diagnostic_msgs/DiagnosticArray]: Panther system diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [panther_msgs/IOState]: Current IO state.
  • hardware/motor_controllers_state [panther_msgs/DriverState]: Current motor controllers' state and error flags.
Service Servers
  • hardware/aux_power_enable [std_srvs/SetBool]: Enables or disables AUX power.
  • hardware/charger_enable [std_srvs/SetBool]: Enables or disables charger.
  • hardware/digital_power_enable [std_srvs/SetBool]: Enables or disables digital power.
  • hardware/e_stop_reset [std_srvs/Trigger]: Resets E-stop.
  • hardware/e_stop_trigger [std_srvs/Trigger]: Triggers E-stop.
  • hardware/fan_enable [std_srvs/SetBool]: Enables or disables fan.
  • hardware/led_control_enable [std_srvs/SetBool]: Enables or disables SBC (Single Board Computer) control over the LEDs.
  • hardware/motor_power_enable [std_srvs/SetBool]: Enables or disables motor power.
Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro).

Physical properties

  • encoder_resolution [int, default: 1600]: Property of the encoder used, shouldn't be changed.
  • gear_ratio [float, default: 30.08]: Property of the gearbox used, shouldn't be changed.
  • motor_torque_constant [float, default: 0.11]: Same as set in the Roboteq driver (TNM parameter), also shouldn't be changed, as it is measured property of the motor.
  • max_rpm_motor_speed [float, default: 3600.0]: Max RPM speed set in the Roboteq driver (MXRPM parameter).
  • gearbox_efficiency [float, default: 0.75]: Measured efficiency, used for converting read current to torque, can vary depending on different factors such as temperature and wear.

CAN settings

  • can_interface_name [string, default: panther_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (set as in canopen_configuration.yaml).
  • front_driver_can_id [int, default: 1]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).
  • rear_driver_can_id [int, default: 2]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).
  • sdo_operation_timeout_ms [int, default: 100]: Timeout of the SDO operations, currently no SDO operation is required in RT operation, so this timeout can be set to a higher value.
  • pdo_motor_states_timeout_ms [int, default: 15]: Depends on the frequency at which Roboteq is configured to send motor states (PDO 1 and 2) data. By default, there should be 10 [ms] between received data, if it takes more than pdo_motor_states_timeout_ms, a motor states read error is triggered. The default value is set to be expected period +50% margin.
  • pdo_driver_state_timeout_ms [int, default: 75]: Depends on the frequency at which Roboteq is configured to send driver state (PDO 3 and 4) data. By default, there should be 50 [ms] between received data, if it takes more than pdo_driver_state_timeout_ms, a driver state read error is triggered. The default value is set to be expected period +50% margin.
  • driver_states_update_frequency [float, default: 20.0]: As by default, the driver state is published with lower frequency, it also shouldn't be updated with every controller loop iteration. The exact frequency at which driver state is published won't match this value - it will also depend on the frequency of the controller (the exact value of the period can be calculated with the following formula controller_frequency / ceil(controller_frequency / driver_states_update_frequency)).
  • max_roboteq_initialization_attempts [int, default: 5]: In some cases, an SDO error can happen during initialization, it is possible to configure more attempts, before escalating to a general error.
  • max_roboteq_activation_attempts [int, default: 5]: Similar to initialization, it is possible to allow some SDO errors before escalating to error.
  • max_write_pdo_cmds_errors_count [int, default: 2]: How many consecutive errors can happen before escalating to general error.
  • max_read_pdo_motor_states_errors_count [int, default: 2]: How many consecutive errors can happen before escalating to general error.
  • max_read_pdo_driver_state_errors_count [int, default: 2]: How many consecutive errors can happen before escalating to general error.
danger

max_write_pdo_cmds_errors_count, max_read_pdo_motor_states_errors_count, max_read_pdo_driver_state_errors_count, sdo_operation_timeout, pdo_motor_states_timeout_ms and pdo_driver_state_timeout_ms are safety-critical parameters, they should be changed only in very specific cases, be sure that you know how they work and be really cautious when changing them.

PantherImuSensor

Plugin responsible for communicating with IMU and filtering data using Madgwick Filter.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro).

Physical properties

  • serial [int, default: -1]: The serial number of the Phidgets Spatial to connect to. If -1 (the default), connects to any Spatial Phidget that can be found.
  • hub_port [int, default: 0]: The Phidgets VINT hub port to connect to. Only used if the Spatial Phidget is connected to a VINT hub. Defaults to 0.
  • heating_enabled [bool, default: false]: Use the internal heating element; just available on MOT0109 onwards. Do not set this parameter for older versions.
  • time_resynchronization_interval_ms [int, default: 5000]: The number of milliseconds to wait between resynchronizing the time on the Phidgets Spatial with the local time. Larger values have less 'jumps', but will have more timestamp drift. Setting this to 0 disables resynchronization. Defaults to 5000 ms.
  • data_interval_ms [int, default: 8]: The number of milliseconds between acquisitions of data on the device (allowed values are dependent on the device). Defaults to 8 ms.
  • callback_delta_epsilon_ms [int, default: 1]: The number of milliseconds epsilon allowed between callbacks when attempting to resynchronize the time. If this is set to 1, then a difference of data_interval_ms plus or minus 1 millisecond will be considered viable for resynchronization. Higher values give the code more leeway to resynchronize, at the cost of potentially getting bad resynchronizations sometimes. Lower values can give better results, but can also result in never resynchronizing. Must be less than data_interval_ms. Defaults to 1 ms.
  • cc_mag_field [double, default: 0.0]: Ambient magnetic field calibration value; see device's user guide for information on how to calibrate.
  • cc_offset0 [double, default: 0.0]: Calibration offset value 0; see device's user guide for information on how to calibrate.
  • cc_offset1 [double, default: 0.0]: Calibration offset value 1; see device's user guide for information on how to calibrate.
  • cc_offset2 [double, default: 0.0]: Calibration offset value 2; see device's user guide for information on how to calibrate.
  • cc_gain0 [double, default: 0.0]: Gain offset value 0; see device's user guide for information on how to calibrate.
  • cc_gain1 [double, default: 0.0]: Gain offset value 1; see device's user guide for information on how to calibrate.
  • cc_gain2 [double, default: 0.0]: Gain offset value 2; see device's user guide for information on how to calibrate.
  • cc_t0 [double, default: 0.0]: T offset value 0; see device's user guide for information on how to calibrate.
  • cc_t1 [double, default: 0.0]: T offset value 1; see device's user guide for information on how to calibrate.
  • cc_t2 [double, default: 0.0]: T offset value 2; see device's user guide for information on how to calibrate.
  • cc_t3 [double, default: 0.0]: T offset value 3; see device's user guide for information on how to calibrate.
  • cc_t4 [double, default: 0.0]: T offset value 4; see device's user guide for information on how to calibrate.
  • cc_t5 [double, default: 0.0]: T offset value 5; see device's user guide for information on how to calibrate.

Madgwick filter settings

  • use_mag [bool, default: false]: Use magnitude to calculate orientation.
  • gain [double, default: 0.1]: Gain of the filter. Higher values lead to faster convergence but more noise. Lower values lead to slower convergence but smoother signal.
  • zeta [double, default: 0.1]: Gyro drift gain (approx. rad/s).
  • mag_bias_x [double, default: 0.0]: Magnetometer bias (hard iron correction), x component.
  • mag_bias_y [double, default: 0.0]: Magnetometer bias (hard iron correction), y component.
  • mag_bias_z [double, default: 0.0]: Magnetometer bias (hard iron correction), z component.
  • stateless [bool, default: false]: Use stateless to compute orientation on every data callback without prediction based on previous measurements.
  • remove_gravity_vector [bool, default: false]: The gravity vector is kept in the IMU message.

The Madgwick Filter parameters, zeta and gain, are provided in the paper "An efficient orientation filter for inertial and inertial/magnetic sensor arrays". The Panther robot utilizes the PhidgetSpatial Precision 3/3/3 IMU sensor, with detailed specifications available on the producer's website.

Gyroscope Noise (@ 1ms) is:

gyroMeasError = 0.2 deg/s = 0.00351 rad/s

Gyroscope Drift Max is:

gyroMeasDrift  = 0.1 deg/s = 0.00175 rad/s

Instructions for computing gain and zeta can be found in the paper.

gain = sqrt(3/4)* gyroMeasError = 0.00303
zeta = sqrt(3/4)* gyroMeasDrift = 0.00151

Code structure

The code structure is described in more detail in a separate file.

Generating CAN config

Adjust your configuration and generate a new master.dcf using: dcfgen canopen_configuration.yaml -r

RT

To configure RT check out the instructions provided in the ros2_control docs (add group and change /etc/security/limits.conf).

Testing

Setup

First, it is necessary to set up a virtual CAN:

sudo modprobe vcan
sudo ip link add dev panther_can type vcan
sudo ip link set up panther_can
sudo ip link set panther_can down
sudo ip link set panther_can txqueuelen 1000
sudo ip link set panther_can up

Running tests

colcon build --packages-select panther_hardware_interfaces --symlink-install
colcon test --event-handlers console_direct+ --packages-select panther_hardware_interfaces --parallel-workers 1
colcon test-result --verbose --all

As some of the tests are accessing the virtual CAN interface, they can't be executed in parallel (that's why --parallel-workers 1 flag).

panther_lights

Package used to control the Husarion Panther Bumper Lights.

Launch files

This package contains:

  • lights.launch.py: Responsible for launching the nodes required to control the Panther Bumper Lights.

Configuration Files

  • led_config.yaml: Defines and describes the appearance and parameters of the animations.

ROS Nodes

LightsControllerNode

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

Publishers
  • lights/channel_1_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: An animation frame to be displayed on robot Front Bumper Lights.
  • lights/channel_2_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: An animation frame to be displayed on robot Rear Bumper Lights.
Service Servers
  • lights/set_animation [panther_msgs/SetLEDAnimation]: Allows setting animation on Bumper Lights based on animation ID.
Parameters
  • ~controller_frequency [float, default: 50.0]: Frequency [Hz] at which the lights controller node will process animations.
  • ~led_config_file [string, default: $(find panther_lights)/panther_lights/config/led_config.yaml]: Path to a YAML file with a description of led configuration. This file includes definition of robot panels, virtual segments and default animations.
  • ~user_led_animations_file [string, default: None]: Path to a YAML file with a description of the user defined animations.

LightsDriverNode

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

Publishers
  • diagnostics [diagnostic_msgs/DiagnosticArray]: Lights diagnostic messages.
Subscribers
  • lights/channel_1_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: Frame to be displayed on robot Front Bumper Lights.
  • lights/channel_2_frame [sensor_msgs/Image, encoding: RGBA8, height: 1, width: num_led]: Frame to be displayed on robot Rear Bumper Lights.
Service Servers
  • lights/set_brightness [panther_msgs/SetLEDBrightness]: Allows setting global LED brightness, value ranges from 0.0 to 1.0.
Service Clients
  • hardware/led_control_enable [std_srvs/SetBool]: Makes SBC controlling LEDs.
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_localization

The package is responsible for activating mods responsible for fusion of data related to the robot's location.

Launch files

This package contains:

  • localization.launch.py: Responsible for activating EKF filtration along with the necessary dependencies needed to operate GPS.
  • nmea_navsat.launch.py: Responsible for launching the NMEA NavSat driver node.

Configuration Files

  • enu_localization.yaml: configures data fusion for ekf_filter and navsat_transform nodes, using wheel encoders and IMU. Orientation follows East-North-Up (ENU) coordinates.
  • enu_localization_with_gps.yaml: configures data fusion for ekf_filter and navsat_transform nodes, using wheel encoders, IMU, and GPS. Orientation follows East-North-Up (ENU) coordinates.
  • nmea_navsat_params.yaml: contains parameters for NMEA NavSat driver node.
  • relative_localization.yaml: configures data fusion for ekf_filter and navsat_transform nodes, using wheel encoders, IMU. The initial orientation is always 0 in relative mode.
  • relative_localization_with_gps.yaml: configures data fusion for ekf_filter and navsat_transform nodes, using wheel encoders, IMU, and GPS. The initial orientation is always 0 in relative mode.

panther_manager

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

Launch Files

This package contains:

  • manager.launch.py: Responsible for launching behavior trees responsible for safety and LED animations scheduling.

Configuration Files

ROS Nodes

lights_manager_node

Node responsible for managing Bumper Lights animation scheduling.

Subscribers
  • battery/battery_status [sensor_msgs/BatteryState]: State of the internal Battery.
  • hardware/e_stop [std_msgs/Bool]: State of emergency stop.
Service Clients (for Default Trees)
  • ~/lights/set_animation [panther_msgs/SetLEDAnimation]: Allows setting animation on Bumper Lights based on animation ID.
Parameters
  • battery.anim_period.critical [float, default: 15.0]: Time in [s] to wait before repeating animation, indicating a critical Battery state.
  • battery.anim_period.low [float, default: 30.0]: Time in [s] to wait before repeating the animation, indicating a low Battery state.
  • battery.charging_anim_step [float, default: 0.1]: This parameter defines the minimum change in battery percentage required to trigger an update in the battery charging animation.
  • battery.percent.threshold.critical [float, default: 0.1]: If the Battery percentage drops below this value, an animation indicating a critical Battery state will start being displayed.
  • battery.percent.threshold.low [float, default: 0.4]: If the Battery percentage drops below this value, the animation indicating a low Battery state will start being displayed.
  • battery.percent.window_len [int, default: 6]: Moving average window length used to smooth out Battery percentage readings.
  • bt_project_path [string, default: $(find panther_manager)/config/PantherBT.btproj]: Path to a BehaviorTree project.
  • plugin_libs [list, default: Empty list]: List with names of plugins that are used in the BT project.
  • ros_communication_timeout.availability [float, default: 1.0]: Timeout [s] to wait for a service/action while initializing BT node.
  • ros_communication_timeout.response [float, default: 1.0]: Timeout [s] to receive a service/action response after call.
  • ros_plugin_libs [list, default: Empty list]: List with names of ROS plugins that are used in a BT project.
  • timer_frequency [float, default: 10.0]: Frequency [Hz] at which lights tree will be ticked.

safety_manager_node

Node responsible for managing safety features, and software shutdown of components.

Subscribers
  • battery/battery_status [sensor_msgs/BatteryState]: State of the internal Battery.
  • hardware/e_stop [std_msgs/Bool]: State of emergency stop.
  • hardware/io_state [panther_msgs/IOState]: State of IO pins.
  • hardware/motor_controllers_state [panther_msgs/DriverState]: State of motor controllers.
  • system_status [panther_msgs/SystemStatus]: Built-in computer system status, includes the most important computation-related parameters.
Service Clients (for Default Trees)
  • ~/hardware/aux_power_enable [std_srvs/SetBool]: Enables Aux Power output.
  • ~/hardware/e_stop_trigger [std_srvs/Trigger]: Triggers E-stop.
  • ~/hardware/fan_enable [std_srvs/SetBool]: Enables fan.
Parameters
  • battery.temp.window_len [int, default: 6]: Moving average window length used to smooth out temperature readings of the Battery.
  • bt_project_path [string, default: $(find panther_manager)/config/PantherBT.btproj]: Path to a BehaviorTree project.
  • cpu.temp.fan_off [float, default: 60.0]: Temperature in [°C] of the Built-in Computer's CPU, below which the fan is turned off.
  • cpu.temp.fan_on [float, default: 70.0]: Temperature in [°C] of the Built-in Computer's CPU, above which the fan is turned on.
  • 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.fan_off [float, default: 35.0]: Temperature in [°C] of any drivers below which the fan is turned off.
  • driver.temp.fan_on [float, default: 45.0]: Temperature in [°C] of any drivers above which the fan is turned on.
  • driver.temp.window_len [int, default: 6]: Moving average window length used to smooth out the temperature readings of each driver.
  • fan_turn_off_timeout [float, default: 60.0]: Minimal time in [s], after which the fan may be turned off.
  • plugin_libs [list, default: Empty list]: List with names of plugins that are used in the BT project.
  • ros_communication_timeout.availability [float, default: 1.0]: Timeout [s] to wait for a service/action while initializing BT node.
  • ros_communication_timeout.response [float, default: 1.0]: Timeout [s] to receive a service/action response after call.
  • ros_plugin_libs [list, default: Empty list]: List with names of ROS plugins that are used in a BT project.
  • shutdown_hosts_path [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.
  • timer_frequency [float, default: 10.0]: Frequency [Hz] at which safety tree will be ticked.

panther_utils

Package containing commonly used functions, classes, and configurations for the Husarion Panther system.