Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.3.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version ros2
Last Updated 2025-05-29
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.3.0 (2025-05-19)

  • Revert "Update changelog"
  • Revert "2.3.0"
  • Revert "2.3.0"
  • Revert "Update changelog"
  • Reapply "Release 2.3.0 to ros2"
  • Merge branch 'ros2' of https://github.com/husarion/husarion_ugv_ros into rel-test
  • Merge pull request #550 from husarion/release-2.3.0
  • 2.3.0
  • Update changelog
  • Merge pull request #549 from husarion/revert-546-release-2.3.0
  • Revert "Release 2.3.0"
  • Merge pull request #548 from husarion/revert-547-2.3.0-20250425
  • Revert "Release 2.3.0 to ros2"
  • Merge pull request #547 from husarion/2.3.0-20250425
  • Merge pull request #546 from husarion/release-2.3.0
  • 2.3.0
  • Update changelog
  • Jalisco fix hw interfaces (#536)
  • Merge pull request #535 from husarion/release-test-fixes
  • fix integration tests
  • Merge remote-tracking branch 'origin/ros2-devel' into change-pat
  • Merge pull request #518 from husarion/jazzy-devel-hw
  • Merge branch 'ros2-devel' into jazzy-devel-hw
  • Update minimal cmake version
  • Use [hardware]{.title-ref} instead of private topic
  • Fix pre-commit
  • Fix deprecation warnings
  • Merge branch 'jazzy-devel-sim' into jazzy-devel-hw
  • Merge branch 'ros2-devel' into jazzy-devel-sim
  • Merge branch 'ros2-devel' into jazzy-devel-sim
  • Merge branch 'jazzy-devel-sim' into jazzy-devel-hw
  • Merge branch 'ros2-devel' into jazzy-devel-sim
  • Pre-commit
  • Build hardware
  • Contributors: Dawid Kmak, Rafal Gorecki, action-bot, github-actions[bot], kmakd, rafal-gorecki, rafal.gorecki

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro kilted showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro rolling showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro ardent showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro bouncy showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro crystal showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro eloquent showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro dashing showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro galactic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro foxy showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro iron showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro lunar showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro jade showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro indigo showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro hydro showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro kinetic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro melodic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange

No version for distro noetic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 2.2.1
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/husarion/husarion_ugv_ros.git
VCS Type git
VCS Version humble
Last Updated 2025-04-04
Dev Status DEVELOPED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

Hardware controller for Husarion UGV

Additional Links

Maintainers

  • Husarion

Authors

  • Jakub Delicat
  • Paweł Irzyk
  • Dawid Kmak
  • Paweł Kowalski
  • Maciej Stępień

husarion_ugv_hardware_interfaces

Package that implements SystemInterface from ros2_control for Husarion UGV.

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_macro.urdf.xacro or lynx_macro.urdf.xacro.

UGVSystem (PantherSystem | LynxSystem)

Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most parts of both systems are similar and are described below. Each plugin is responsible for communicating with engine controllers via the CAN bus, providing E-Stop functionality, and managing the built-in computer’s GPIO ports.

Publishers

  • diagnostics [diagnostic_msgs/DiagnosticArray]: System diagnostic messages.
  • hardware/e_stop [std_msgs/Bool]: Current E-stop state.
  • hardware/io_state [husarion_ugv_msgs/IOState]: Current IO state.
  • hardware/robot_driver_state [husarion_ugv_msgs/RobotDriverState]: 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_torque_enable [std_srvs/SetBool]: Allows to enable/disable motor torque when the E-Stop is triggered.

Parameters

Required parameters are defined when including the interface in the URDF (you can check out panther_macro.urdf.xacro or lynx_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: robot_can]: Name of the CAN interface.
  • master_can_id [int, default: 3]: CAN ID of the master device (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.

PantherSystem additional CAN settings

  • 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, Required only for PantherSystem]: CAN ID defined in the properties of Roboteq (set as in canopen_configuration.yaml).

LynxSystem additional CAN settings

[!CAUTION] 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.

PhidgetImuSensor

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 or lynx_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

File truncated at 100 lines see the full file

CHANGELOG

\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package husarion_ugv_hardware_interfaces \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^

2.2.1 (2025-04-04)

2.2.0 (2025-03-13)

  • Fix roboteq robot driver deinitialization (#504)
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-devel
  • Merge pull request #496 from husarion/repo-rename
  • update links
  • Merge branch 'ros2-devel' into lights-new
  • Merge pull request #490 from husarion/ros2-fix-bild-warnings
  • fix build warnings
  • Ros2 unit test workflow (#471)
  • Merge pull request #479 from husarion/e_stop_torque_enable
  • Change method name
  • Rename to motor_torque_enable
  • Merge remote-tracking branch 'origin/ros2-devel' into e_stop_torque_enable
  • Rename service e_stop_torque_enable
  • Add suggestions
  • Merge pull request #480 from husarion/ros2-cmake-export
  • Add ament_index_cpp dependency
  • Add exports to cmake
  • use throw to sen failed response
  • Ros2 motor enable fix (#478)
  • Change logic from [motor_power_enable]{.title-ref} to [e_stop_torque_enable]{.title-ref}
  • Remove last new line
  • Only fix logs
  • Add motor enable set pin function
  • Parameters reorganisation (#472)
  • Merge lynx_description and panther_description into husarion_ugv_descriptions (#456)
  • Merge pull request #466 from husarion/ros2-add-msgs
  • Merge branch 'ros2-devel' into ros2-add-msgs
  • Merge branch 'ros2-devel' into add-panther-diagnostics-config
  • husarion_ugv_msg -> husarion_ugv_msgs
  • Merge remote-tracking branch 'origin/ros2-devel' into ros2-devel
  • Add husarion_ugv_msgs
  • Merge pull request #457 from husarion/ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • Merge branch 'ros2-devel' of https://github.com/husarion/panther_ros into ros2-lynx-devel
  • fix CHRG_DISABLE init state (#447)
  • Update gpio controller (#425)
  • Ros2 husarion ugv v2 (#422)
  • Contributors: BOOTCFG, Dawid Kmak, Jakub Delicat, Rafal Gorecki, Stefan, kmakd, rafal-gorecki

2.1.2 (2024-12-02)

  • Ros2 fix led bug (#441)
  • Merge branch 'ros2-devel' into ros2-lights-tests
  • Contributors: Dawid Kmak, pawelirh

2.1.1 (2024-09-05)

  • Merge branch 'ros2-devel' into ros2-ns-refactor

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged husarion_ugv_hardware_interfaces at Robotics Stack Exchange