From d501fb717630a5ca15accdb3e6f4a1915b6da5fd Mon Sep 17 00:00:00 2001 From: rafal-gorecki Date: Wed, 11 Dec 2024 08:28:01 +0100 Subject: [PATCH 1/3] Add husarion_ugv_msgs --- .github/workflows/release-candidate.yaml | 2 +- .github/workflows/release-project.yaml | 17 ---- ROS_API.md | 12 +-- husarion_ugv/hardware_deps.repos | 4 - husarion_ugv/package.xml | 2 +- husarion_ugv/simulation_deps.repos | 10 +- husarion_ugv_battery/CMakeLists.txt | 10 +- husarion_ugv_battery/README.md | 6 +- .../husarion_ugv_battery/battery/battery.hpp | 4 +- .../battery/roboteq_battery.hpp | 8 +- .../battery_driver_node.hpp | 4 +- .../battery_publisher/battery_publisher.hpp | 8 +- husarion_ugv_battery/package.xml | 4 +- .../test/battery/test_adc_battery.cpp | 4 +- .../test/battery/test_battery.cpp | 4 +- .../test/battery/test_roboteq_battery.cpp | 10 +- .../test_battery_publisher.cpp | 4 +- .../test_dual_battery_publisher.cpp | 4 +- .../test/test_battery_driver_node_roboteq.cpp | 4 +- .../test/utils/test_battery_driver_node.hpp | 8 +- husarion_ugv_bringup/package.xml | 2 +- husarion_ugv_controller/package.xml | 2 +- husarion_ugv_diagnostics/CMakeLists.txt | 2 +- husarion_ugv_diagnostics/README.md | 2 +- .../system_monitor_node.hpp | 6 +- husarion_ugv_diagnostics/package.xml | 4 +- .../src/system_monitor_node.cpp | 8 +- .../integration/system_monitor_node.test.py | 3 +- .../test/unit/test_system_monitor_node.cpp | 2 +- husarion_ugv_gazebo/package.xml | 2 +- .../CMakeLists.txt | 24 ++--- husarion_ugv_hardware_interfaces/README.md | 4 +- .../robot_driver/roboteq_data_converters.hpp | 12 +-- .../robot_system/system_ros_interface.hpp | 12 +-- husarion_ugv_hardware_interfaces/package.xml | 4 +- .../robot_driver/roboteq_data_converters.cpp | 12 +-- .../test_roboteq_data_converters.cpp | 6 +- .../test_system_ros_interface.cpp | 2 +- husarion_ugv_lights/CMakeLists.txt | 6 +- husarion_ugv_lights/CONFIGURATION.md | 2 +- husarion_ugv_lights/README.md | 4 +- .../lights_controller_node.hpp | 4 +- .../lights_driver_node.hpp | 4 +- husarion_ugv_lights/package.xml | 4 +- .../src/lights_controller_node.cpp | 2 +- .../src/lights_driver_node.cpp | 2 +- .../integration/husarion_ugv_lights.test.py | 5 +- .../test/unit/test_lights_driver_node.cpp | 4 +- husarion_ugv_localization/package.xml | 2 +- husarion_ugv_manager/CMakeLists.txt | 14 +-- husarion_ugv_manager/CONFIGURATION.md | 22 ++--- husarion_ugv_manager/README.md | 8 +- .../lights_manager_node.hpp | 4 +- .../call_set_led_animation_service_node.hpp | 6 +- .../safety_manager_node.hpp | 12 +-- husarion_ugv_manager/package.xml | 4 +- ...st_call_set_led_animation_service_node.cpp | 16 ++-- .../test/test_lights_behavior_tree.cpp | 8 +- .../test/test_safety_behavior_tree.cpp | 8 +- .../test/test_safety_manager_node.cpp | 8 +- .../test/utils/plugin_test_utils.hpp | 2 +- husarion_ugv_msg/CHANGELOG.rst | 95 +++++++++++++++++++ husarion_ugv_msg/CMakeLists.txt | 35 +++++++ husarion_ugv_msg/README.md | 3 + husarion_ugv_msg/msg/ChargingStatus.msg | 13 +++ husarion_ugv_msg/msg/DriverState.msg | 14 +++ husarion_ugv_msg/msg/DriverStateNamed.msg | 6 ++ husarion_ugv_msg/msg/FaultFlag.msg | 8 ++ husarion_ugv_msg/msg/IOState.msg | 8 ++ husarion_ugv_msg/msg/LEDAnimation.msg | 13 +++ husarion_ugv_msg/msg/LEDAnimationQueue.msg | 1 + husarion_ugv_msg/msg/LEDImageAnimation.msg | 5 + husarion_ugv_msg/msg/RobotDriverState.msg | 8 ++ husarion_ugv_msg/msg/RuntimeError.msg | 7 ++ husarion_ugv_msg/msg/ScriptFlag.msg | 3 + husarion_ugv_msg/msg/SystemStatus.msg | 7 ++ husarion_ugv_msg/package.xml | 29 ++++++ husarion_ugv_msg/srv/SetLEDAnimation.srv | 5 + husarion_ugv_msg/srv/SetLEDBrightness.srv | 4 + husarion_ugv_msg/srv/SetLEDImageAnimation.srv | 7 ++ husarion_ugv_utils/package.xml | 2 +- 81 files changed, 455 insertions(+), 207 deletions(-) create mode 100644 husarion_ugv_msg/CHANGELOG.rst create mode 100644 husarion_ugv_msg/CMakeLists.txt create mode 100644 husarion_ugv_msg/README.md create mode 100644 husarion_ugv_msg/msg/ChargingStatus.msg create mode 100644 husarion_ugv_msg/msg/DriverState.msg create mode 100644 husarion_ugv_msg/msg/DriverStateNamed.msg create mode 100644 husarion_ugv_msg/msg/FaultFlag.msg create mode 100644 husarion_ugv_msg/msg/IOState.msg create mode 100644 husarion_ugv_msg/msg/LEDAnimation.msg create mode 100644 husarion_ugv_msg/msg/LEDAnimationQueue.msg create mode 100644 husarion_ugv_msg/msg/LEDImageAnimation.msg create mode 100644 husarion_ugv_msg/msg/RobotDriverState.msg create mode 100644 husarion_ugv_msg/msg/RuntimeError.msg create mode 100644 husarion_ugv_msg/msg/ScriptFlag.msg create mode 100644 husarion_ugv_msg/msg/SystemStatus.msg create mode 100644 husarion_ugv_msg/package.xml create mode 100644 husarion_ugv_msg/srv/SetLEDAnimation.srv create mode 100644 husarion_ugv_msg/srv/SetLEDBrightness.srv create mode 100644 husarion_ugv_msg/srv/SetLEDImageAnimation.srv diff --git a/.github/workflows/release-candidate.yaml b/.github/workflows/release-candidate.yaml index f2744f57d..b06bddd69 100644 --- a/.github/workflows/release-candidate.yaml +++ b/.github/workflows/release-candidate.yaml @@ -44,7 +44,7 @@ jobs: - unit_test_panther_ros strategy: matrix: - repo: [panther_ros, panther_msgs, panther-docker, panther-rpi-os-img] + repo: [panther_ros, panther-docker, panther-rpi-os-img] steps: - name: Create test branch uses: GuillaumeFalourd/create-other-repo-branch-action@v1.5 diff --git a/.github/workflows/release-project.yaml b/.github/workflows/release-project.yaml index 4ac40ef26..cc4307e05 100644 --- a/.github/workflows/release-project.yaml +++ b/.github/workflows/release-project.yaml @@ -34,23 +34,6 @@ jobs: name: Release Husarion UGV project runs-on: ubuntu-22.04 steps: - - name: Release panther_msgs repository - uses: convictional/trigger-workflow-and-wait@v1.6.1 - with: - owner: husarion - repo: panther_msgs - github_token: ${{ secrets.GH_PAT }} - workflow_file_name: release-repository.yaml - ref: ${{ env.RC_BRANCH_NAME }} - client_payload: | - { - "release_candidate": "${{ env.RC_BRANCH_NAME }}", - "version": "${{ github.event.inputs.version }}", - "release_name": "${{ github.event.inputs.release_name }}", - "automatic_mode": "${{ github.event.inputs.automatic_mode }}", - "prerelease": "${{ github.event.inputs.prerelease }}" - } - - name: Release panther_ros repository uses: convictional/trigger-workflow-and-wait@v1.6.1 with: diff --git a/ROS_API.md b/ROS_API.md index f29c06646..7522843fc 100644 --- a/ROS_API.md +++ b/ROS_API.md @@ -68,7 +68,7 @@ Below is information about the physical robot API. For the simulation, topics an | 🤖 | 🖥️ | Topic | Description | | --- | --- | ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | ✅ | ✅ | `battery/battery_status` | Mean values of both batteries will be published if the robot has two batteries. Otherwise, the state of the single battery will be published.
[*sensor_msgs/BatteryState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/BatteryState.html) | -| ✅ | ❌ | `battery/charging_status` | Battery charging status value.
[*panther_msgs/ChargingStatus*](https://github.com/husarion/panther_msgs) | +| ✅ | ❌ | `battery/charging_status` | Battery charging status value.
[*husarion_ugv_msg/ChargingStatus*](https://github.com/husarion/husarion_ugv_msg) | | ✅ | ✅ | `cmd_vel` | Command velocity value.
[*geometry_msgs/Twist*](https://docs.ros2.org/latest/api/geometry_msgs/msg/Twist.html) | | ✅ | ✅ | `diagnostics` | Diagnostic data.
[*diagnostic_msgs/DiagnosticArray*](https://docs.ros2.org/latest/api/diagnostic_msgs/msg/DiagnosticArray.html) | | ✅ | ✅ | `dynamic_joint_states` | Information about the state of various movable joints in a robotic system.
[*control_msgs/DynamicJointState*](https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/DynamicJointState.msg) | @@ -77,8 +77,8 @@ Below is information about the physical robot API. For the simulation, topics an | ✅ | ❌ | `gps/time_reference` | The timestamp from the GPS device.
[*sensor_msgs/TimeReference*](https://docs.ros2.org/latest/api/sensor_msgs/msg/TimeReference.html) | | ✅ | ❌ | `gps/vel` | Velocity output from the GPS device.
[*geometry_msgs/TwistStamped*](https://docs.ros2.org/latest/api/geometry_msgs/msg/TwistStamped.html) | | ✅ | ✅ | `hardware/e_stop` | Current E-stop state.
[*std_msgs/Bool*](https://docs.ros2.org/latest/api/std_msgs/msg/Bool.html). | -| ✅ | ❌ | `hardware/io_state` | Current IO state.
[*panther_msgs/IOState*](https://github.com/husarion/panther_msgs) | -| ✅ | ✅ | `hardware/robot_driver_state` | Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
[*panther_msgs/RobotDriverState*](https://github.com/husarion/panther_msgs) | +| ✅ | ❌ | `hardware/io_state` | Current IO state.
[*husarion_ugv_msg/IOState*](https://github.com/husarion/husarion_ugv_msg) | +| ✅ | ✅ | `hardware/robot_driver_state` | Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
[*husarion_ugv_msg/RobotDriverState*](https://github.com/husarion/husarion_ugv_msg) | | ✅ | ✅ | `imu/data` | Filtered IMU data.
[*sensor_msgs/Imu*](https://docs.ros2.org/latest/api/sensor_msgs/msg/Imu.html) | | ✅ | ✅ | `joint_states` | Provides information about the state of various joints in a robotic system.
[*sensor_msgs/JointState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/JointState.html) | | ✅ | ✅ | `lights/channel_1_frame` | Frame to be displayed on robot Front Bumper Lights.
[*sensor_msgs/Image*](https://docs.ros2.org/latest/api/sensor_msgs/msg/Image.html) | @@ -87,7 +87,7 @@ Below is information about the physical robot API. For the simulation, topics an | ✅ | ✅ | `odometry/filtered` | Contains information about the filtered position and orientation. When `localization_mode` is `relative`, the position and orientation are relative to the starting point. When `localization_mode` is `enu`, the orientation is relative to the east-north-up (ENU) coordinates.
[*nav_msgs/Odometry*](https://docs.ros2.org/latest/api/nav_msgs/msg/Odometry.html) | | ✅ | ✅ | `odometry/wheels` | Robot odometry calculated from wheels.
[*nav_msgs/Odometry*](https://docs.ros2.org/latest/api/nav_msgs/msg/Odometry.html) | | ✅ | ✅ | `robot_description` | Contains information about robot description from URDF file.
[*std_msgs/String*](https://docs.ros2.org/latest/api/std_msgs/msg/String.html) | -| ✅ | ❌ | `system_status` | State of the system, including Built-in Computer's CPU temperature and load.
[*panther_msgs/SystemStatus*](https://github.com/husarion/panther_msgs) | +| ✅ | ❌ | `system_status` | State of the system, including Built-in Computer's CPU temperature and load.
[*husarion_ugv_msg/SystemStatus*](https://github.com/husarion/husarion_ugv_msg) | | ✅ | ✅ | `tf` | Transforms of robot system.
[*tf2_msgs/TFMessage*](https://docs.ros2.org/latest/api/tf2_msgs/msg/TFMessage.html) | | ✅ | ✅ | `tf_static` | Static transforms of robot system.
[*tf2_msgs/TFMessage*](https://docs.ros2.org/latest/api/tf2_msgs/msg/TFMessage.html) | @@ -121,8 +121,8 @@ Below is information about the physical robot API. For the simulation, topics an | ✅ | ✅ | `hardware/e_stop_trigger` | Triggers E-stop.
[std_srvs/srv/Trigger](https://docs.ros2.org/latest/api/std_srvs/srv/Trigger.html) | | ✅ | ❌ | `hardware/fan_enable` | Enables or disables fan.
[std_srvs/srv/SetBool](https://docs.ros2.org/latest/api/std_srvs/srv/SetBool.html) | | ✅ | ❌ | `hardware/motor_power_enable` | Enables or disables motor power.
[std_srvs/srv/SetBool](https://docs.ros2.org/latest/api/std_srvs/srv/SetBool.html) | -| ✅ | ✅ | `lights/set_animation` | Sets LED animation.
[panther_msgs/srv/SetLEDAnimation](https://github.com/husarion/panther_msgs) | +| ✅ | ✅ | `lights/set_animation` | Sets LED animation.
[husarion_ugv_msg/srv/SetLEDAnimation](https://github.com/husarion/husarion_ugv_msg) | | ✅ | ✅ | `localization/enable` | Enable EKF node.
[std_srvs/srv/Empty](https://docs.ros2.org/latest/api/std_srvs/srv/Empty.html) | -| ✅ | ❌ | `lights/set_brightness` | Sets global LED brightness, value ranges from **0.0** to **1.0**.
[panther_msgs/SetLEDBrightness](https://github.com/husarion/panther_msgs) | +| ✅ | ❌ | `lights/set_brightness` | Sets global LED brightness, value ranges from **0.0** to **1.0**.
[husarion_ugv_msg/SetLEDBrightness](https://github.com/husarion/husarion_ugv_msg) | | ✅ | ✅ | `localization/set_pose` | Set pose of EKF node.
[robot_localization/srv/SetPose](https://github.com/cra-ros-pkg/robot_localization/tree/ros2) | | ✅ | ✅ | `localization/toggle` | Toggle filter processing in the EKF node.
[robot_localization/srv/ToggleFilterProcessing](https://github.com/cra-ros-pkg/robot_localization/tree/ros2) | diff --git a/husarion_ugv/hardware_deps.repos b/husarion_ugv/hardware_deps.repos index 171ec29fe..77ced26e1 100644 --- a/husarion_ugv/hardware_deps.repos +++ b/husarion_ugv/hardware_deps.repos @@ -7,10 +7,6 @@ repositories: type: git url: https://github.com/husarion/husarion_controllers version: d184d9b5936ec3f51084b70dc7d3825fa5ecaee0 - panther_msgs: - type: git - url: https://github.com/husarion/panther_msgs.git - version: ros2-lynx-devel ros_components_description: type: git url: https://github.com/husarion/ros_components_description.git diff --git a/husarion_ugv/package.xml b/husarion_ugv/package.xml index e426e3876..1a9fd9233 100644 --- a/husarion_ugv/package.xml +++ b/husarion_ugv/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues diff --git a/husarion_ugv/simulation_deps.repos b/husarion_ugv/simulation_deps.repos index a754ab3eb..83bab93e8 100644 --- a/husarion_ugv/simulation_deps.repos +++ b/husarion_ugv/simulation_deps.repos @@ -7,10 +7,10 @@ repositories: type: git url: https://github.com/husarion/husarion_controllers version: d184d9b5936ec3f51084b70dc7d3825fa5ecaee0 - panther_msgs: + husarion_gz_worlds: type: git - url: https://github.com/husarion/panther_msgs.git - version: ros2-lynx-devel + url: https://github.com/husarion/husarion_gz_worlds.git + version: 9d514a09c74bca2afbfba76cf2c87134918bbf97 ros_components_description: type: git url: https://github.com/husarion/ros_components_description.git @@ -19,7 +19,3 @@ repositories: type: git url: https://github.com/husarion/ros2_controllers/ version: 9da42a07a83bbf3faf5cad11793fff22f25068af - husarion_gz_worlds: - type: git - url: https://github.com/husarion/husarion_gz_worlds.git - version: 9d514a09c74bca2afbfba76cf2c87134918bbf97 diff --git a/husarion_ugv_battery/CMakeLists.txt b/husarion_ugv_battery/CMakeLists.txt index d928de579..91a52e789 100644 --- a/husarion_ugv_battery/CMakeLists.txt +++ b/husarion_ugv_battery/CMakeLists.txt @@ -5,7 +5,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater panther_msgs +set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs) foreach(PACKAGE IN ITEMS ${PACKAGE_DEPENDENCIES}) @@ -45,7 +45,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_battery rclcpp sensor_msgs - panther_msgs) + husarion_ugv_msg) ament_add_gtest(${PROJECT_NAME}_test_adc_battery test/battery/test_adc_battery.cpp src/battery/adc_battery.cpp) @@ -54,7 +54,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_adc_battery rclcpp sensor_msgs - panther_msgs) + husarion_ugv_msg) ament_add_gtest( ${PROJECT_NAME}_test_roboteq_battery test/battery/test_roboteq_battery.cpp @@ -63,8 +63,8 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_roboteq_battery PUBLIC $ $) - ament_target_dependencies(${PROJECT_NAME}_test_roboteq_battery panther_msgs - rclcpp sensor_msgs) + ament_target_dependencies(${PROJECT_NAME}_test_roboteq_battery + husarion_ugv_msg rclcpp sensor_msgs) ament_add_gtest( ${PROJECT_NAME}_test_battery_publisher diff --git a/husarion_ugv_battery/README.md b/husarion_ugv_battery/README.md index a6fcc35fe..cc67f082f 100644 --- a/husarion_ugv_battery/README.md +++ b/husarion_ugv_battery/README.md @@ -19,13 +19,13 @@ Publishes battery state read from ADC unit. - `_battery/battery_1_status_raw` [*sensor_msgs/BatteryState*]: First battery raw state. - `_battery/battery_2_status_raw` [*sensor_msgs/BatteryState*]: Second battery raw state. Published if second battery detected. - `battery/battery_status` [*sensor_msgs/BatteryState*]: Mean values of both batteries if robot has two batteries. Otherwise, the state of the single battery will be published. -- `battery/charging_status` [*panther_msgs/ChargingStatus*]: Battery charging status. +- `battery/charging_status` [*husarion_ugv_msg/ChargingStatus*]: Battery charging status. - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: Battery diagnostic messages. #### Subscribers -- `hardware/io_state` [*panther_msgs/IOState*]: Current state of IO. -- `hardware/robot_driver_state` [*panther_msgs/RobotDriverState*]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data. +- `hardware/io_state` [*husarion_ugv_msg/IOState*]: Current state of IO. +- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data. #### Parameters diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp index 7e461cfa4..8a914c547 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp @@ -25,13 +25,13 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/charging_status.hpp" +#include "husarion_ugv_msg/msg/charging_status.hpp" namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = panther_msgs::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; class Battery { diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp index 0b785f79f..8423d4b83 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp @@ -21,8 +21,8 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_msgs/msg/driver_state_named.hpp" -#include "panther_msgs/msg/robot_driver_state.hpp" +#include "husarion_ugv_msg/msg/driver_state_named.hpp" +#include "husarion_ugv_msg/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/battery/battery.hpp" #include "husarion_ugv_utils/moving_average.hpp" @@ -30,8 +30,8 @@ namespace husarion_ugv_battery { -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; -using DriverStateNamedMsg = panther_msgs::msg::DriverStateNamed; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using DriverStateNamedMsg = husarion_ugv_msg::msg::DriverStateNamed; struct RoboteqBatteryParams { diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp index 1bba8b993..ea9069f83 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp @@ -21,7 +21,7 @@ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" -#include "panther_msgs/msg/robot_driver_state.hpp" +#include "husarion_ugv_msg/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/adc_data_reader.hpp" #include "husarion_ugv_battery/battery/battery.hpp" @@ -30,7 +30,7 @@ namespace husarion_ugv_battery { -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; class BatteryDriverNode : public rclcpp::Node { diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp index 9258b9a51..51b166a49 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp @@ -22,15 +22,15 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/charging_status.hpp" -#include "panther_msgs/msg/io_state.hpp" +#include "husarion_ugv_msg/msg/charging_status.hpp" +#include "husarion_ugv_msg/msg/io_state.hpp" namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = panther_msgs::msg::ChargingStatus; -using IOStateMsg = panther_msgs::msg::IOState; +using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; +using IOStateMsg = husarion_ugv_msg::msg::IOState; class BatteryPublisher { diff --git a/husarion_ugv_battery/package.xml b/husarion_ugv_battery/package.xml index 70f025d7e..c75ea9aa5 100644 --- a/husarion_ugv_battery/package.xml +++ b/husarion_ugv_battery/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues @@ -17,8 +17,8 @@ ament_cmake diagnostic_updater + husarion_ugv_msg husarion_ugv_utils - panther_msgs rclcpp sensor_msgs diff --git a/husarion_ugv_battery/test/battery/test_adc_battery.cpp b/husarion_ugv_battery/test/battery/test_adc_battery.cpp index 9486c85ef..53607796c 100644 --- a/husarion_ugv_battery/test/battery/test_adc_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_adc_battery.cpp @@ -22,13 +22,13 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/charging_status.hpp" +#include "husarion_ugv_msg/msg/charging_status.hpp" #include "husarion_ugv_battery/battery/adc_battery.hpp" #include "husarion_ugv_utils/test/test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = panther_msgs::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; class TestADCBattery : public testing::Test { diff --git a/husarion_ugv_battery/test/battery/test_battery.cpp b/husarion_ugv_battery/test/battery/test_battery.cpp index 9b2d12c0d..5f5536bf5 100644 --- a/husarion_ugv_battery/test/battery/test_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_battery.cpp @@ -22,13 +22,13 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/charging_status.hpp" +#include "husarion_ugv_msg/msg/charging_status.hpp" #include "husarion_ugv_battery/battery/battery.hpp" #include "husarion_ugv_utils/test/test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = panther_msgs::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; class BatteryWrapper : public husarion_ugv_battery::Battery { diff --git a/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp b/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp index 26674df87..089e989d7 100644 --- a/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp @@ -24,14 +24,14 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/driver_state_named.hpp" -#include "panther_msgs/msg/robot_driver_state.hpp" +#include "husarion_ugv_msg/msg/driver_state_named.hpp" +#include "husarion_ugv_msg/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/battery/roboteq_battery.hpp" #include "husarion_ugv_utils/test/test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; class RoboteqBatteryWrapper : public husarion_ugv_battery::RoboteqBattery { @@ -81,8 +81,8 @@ void TestRoboteqBattery::UpdateBattery(const float voltage, const float current) { if (!driver_state_) { driver_state_ = std::make_shared(); - driver_state_->driver_states.push_back(panther_msgs::msg::DriverStateNamed()); - driver_state_->driver_states.push_back(panther_msgs::msg::DriverStateNamed()); + driver_state_->driver_states.push_back(husarion_ugv_msg::msg::DriverStateNamed()); + driver_state_->driver_states.push_back(husarion_ugv_msg::msg::DriverStateNamed()); } auto stamp = rclcpp::Time(0, 0, RCL_ROS_TIME); diff --git a/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp index f5924c731..249c3193f 100644 --- a/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp @@ -22,12 +22,12 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/io_state.hpp" +#include "husarion_ugv_msg/msg/io_state.hpp" #include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using IOStateMsg = panther_msgs::msg::IOState; +using IOStateMsg = husarion_ugv_msg::msg::IOState; class BatteryPublisherWrapper : public husarion_ugv_battery::BatteryPublisher { diff --git a/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp index 74bcb3581..959febfc4 100644 --- a/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp @@ -22,7 +22,7 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/charging_status.hpp" +#include "husarion_ugv_msg/msg/charging_status.hpp" #include "husarion_ugv_battery/battery/adc_battery.hpp" #include "husarion_ugv_battery/battery/battery.hpp" @@ -30,7 +30,7 @@ #include "husarion_ugv_utils/test/ros_test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = panther_msgs::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; class DualBatteryPublisherWrapper : public husarion_ugv_battery::DualBatteryPublisher { diff --git a/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp b/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp index 8393b1b9f..5e02ab8cd 100644 --- a/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp +++ b/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp @@ -44,7 +44,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryValues) EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_STATUS_UNKNOWN, battery_state_->power_supply_status); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_HEALTH_UNKNOWN, battery_state_->power_supply_health); - panther_msgs::msg::DriverStateNamed motor_controller; + husarion_ugv_msg::msg::DriverStateNamed motor_controller; motor_controller.state.voltage = 35.0f; motor_controller.state.current = 0.1f; @@ -84,7 +84,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryTimeout) EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_HEALTH_UNKNOWN, battery_state_->power_supply_health); // Publish some values - panther_msgs::msg::DriverStateNamed motor_controller; + husarion_ugv_msg::msg::DriverStateNamed motor_controller; motor_controller.state.voltage = 35.0f; motor_controller.state.current = 0.1f; diff --git a/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp b/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp index 319dfd6db..5e061fbda 100644 --- a/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp +++ b/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp @@ -28,14 +28,14 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_msgs/msg/io_state.hpp" -#include "panther_msgs/msg/robot_driver_state.hpp" +#include "husarion_ugv_msg/msg/io_state.hpp" +#include "husarion_ugv_msg/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/battery_driver_node.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; -using IOStateMsg = panther_msgs::msg::IOState; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using IOStateMsg = husarion_ugv_msg::msg::IOState; class TestBatteryNode : public testing::Test { diff --git a/husarion_ugv_bringup/package.xml b/husarion_ugv_bringup/package.xml index c2bcda573..020b6438e 100644 --- a/husarion_ugv_bringup/package.xml +++ b/husarion_ugv_bringup/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues diff --git a/husarion_ugv_controller/package.xml b/husarion_ugv_controller/package.xml index 606766aa1..129ac68f7 100644 --- a/husarion_ugv_controller/package.xml +++ b/husarion_ugv_controller/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues diff --git a/husarion_ugv_diagnostics/CMakeLists.txt b/husarion_ugv_diagnostics/CMakeLists.txt index 64b9751d5..35282f60b 100644 --- a/husarion_ugv_diagnostics/CMakeLists.txt +++ b/husarion_ugv_diagnostics/CMakeLists.txt @@ -20,7 +20,7 @@ set(PACKAGE_DEPENDENCIES diagnostic_msgs diagnostic_updater generate_parameter_library - panther_msgs + husarion_ugv_msg husarion_ugv_utils PkgConfig rclcpp diff --git a/husarion_ugv_diagnostics/README.md b/husarion_ugv_diagnostics/README.md index 02d370216..78440b1bf 100644 --- a/husarion_ugv_diagnostics/README.md +++ b/husarion_ugv_diagnostics/README.md @@ -19,7 +19,7 @@ Publishes the built-in computer system status , monitoring parameters as such as #### Publishes - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: System monitor diagnostic messages. -- `system_status` [*panther_msgs/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. +- `system_status` [*husarion_ugv_msg/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. #### Parameters diff --git a/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp index 0532822f6..4941b9be7 100644 --- a/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp +++ b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp @@ -20,7 +20,7 @@ #include #include -#include "panther_msgs/msg/system_status.hpp" +#include "husarion_ugv_msg/msg/system_status.hpp" #include "system_monitor_parameters.hpp" @@ -63,7 +63,7 @@ class SystemMonitorNode : public rclcpp::Node * @param status The SystemStatus object to be converted. * @return The converted SystemStatus message. */ - panther_msgs::msg::SystemStatus SystemStatusToMessage(const SystemStatus & status); + husarion_ugv_msg::msg::SystemStatus SystemStatusToMessage(const SystemStatus & status); private: void TimerCallback(); @@ -73,7 +73,7 @@ class SystemMonitorNode : public rclcpp::Node diagnostic_updater::Updater diagnostic_updater_; rclcpp::TimerBase::SharedPtr timer_; - rclcpp::Publisher::SharedPtr system_status_publisher_; + rclcpp::Publisher::SharedPtr system_status_publisher_; system_monitor::Params params_; std::shared_ptr param_listener_; diff --git a/husarion_ugv_diagnostics/package.xml b/husarion_ugv_diagnostics/package.xml index fe6258e05..98beb7625 100644 --- a/husarion_ugv_diagnostics/package.xml +++ b/husarion_ugv_diagnostics/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues @@ -20,8 +20,8 @@ diagnostic_msgs diagnostic_updater generate_parameter_library + husarion_ugv_msg husarion_ugv_utils - panther_msgs rclcpp std_msgs diff --git a/husarion_ugv_diagnostics/src/system_monitor_node.cpp b/husarion_ugv_diagnostics/src/system_monitor_node.cpp index f25bcbe3e..bdcf20e11 100644 --- a/husarion_ugv_diagnostics/src/system_monitor_node.cpp +++ b/husarion_ugv_diagnostics/src/system_monitor_node.cpp @@ -22,7 +22,7 @@ #include #include -#include "panther_msgs/msg/system_status.hpp" +#include "husarion_ugv_msg/msg/system_status.hpp" #include "husarion_ugv_utils/common_utilities.hpp" #include "husarion_ugv_utils/ros_utils.hpp" @@ -44,7 +44,7 @@ SystemMonitorNode::SystemMonitorNode( std::make_shared(this->get_node_parameters_interface()); params_ = param_listener_->get_params(); - system_status_publisher_ = this->create_publisher( + system_status_publisher_ = this->create_publisher( "system_status", 10); const auto timer_interval_ms = static_cast(1000.0 / params_.publish_frequency); @@ -149,10 +149,10 @@ float SystemMonitorNode::GetDiskUsage() const return disk_usage; } -panther_msgs::msg::SystemStatus SystemMonitorNode::SystemStatusToMessage( +husarion_ugv_msg::msg::SystemStatus SystemMonitorNode::SystemStatusToMessage( const SystemStatus & status) { - panther_msgs::msg::SystemStatus message; + husarion_ugv_msg::msg::SystemStatus message; message.header.stamp = this->get_clock()->now(); message.cpu_percent = status.core_usages; diff --git a/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py b/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py index 53b34bd49..e5d5df434 100644 --- a/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py +++ b/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py @@ -23,7 +23,8 @@ from launch import LaunchDescription from launch_ros.actions import Node from launch_testing_ros import WaitForTopics -from panther_msgs.msg import SystemStatus + +from husarion_ugv_msg.msg import SystemStatus @pytest.mark.launch_test diff --git a/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp b/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp index dd6ad0538..c48ca35c9 100644 --- a/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp +++ b/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp @@ -62,7 +62,7 @@ class SystemMonitorNodeWrapper : public husarion_ugv_diagnostics::SystemMonitorN float GetDiskUsage() const { return husarion_ugv_diagnostics::SystemMonitorNode::GetDiskUsage(); } - panther_msgs::msg::SystemStatus SystemStatusToMessage( + husarion_ugv_msg::msg::SystemStatus SystemStatusToMessage( const husarion_ugv_diagnostics::SystemStatus & status) { diff --git a/husarion_ugv_gazebo/package.xml b/husarion_ugv_gazebo/package.xml index 7f76d0f74..ee60c30de 100644 --- a/husarion_ugv_gazebo/package.xml +++ b/husarion_ugv_gazebo/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues diff --git a/husarion_ugv_hardware_interfaces/CMakeLists.txt b/husarion_ugv_hardware_interfaces/CMakeLists.txt index 66d2aeff8..2036cda09 100644 --- a/husarion_ugv_hardware_interfaces/CMakeLists.txt +++ b/husarion_ugv_hardware_interfaces/CMakeLists.txt @@ -23,7 +23,7 @@ set(PACKAGE_DEPENDENCIES geometry_msgs hardware_interface imu_filter_madgwick - panther_msgs + husarion_ugv_msg husarion_ugv_utils phidgets_api PkgConfig @@ -100,7 +100,7 @@ if(BUILD_TESTING) test/phidget_imu_sensor/test_phidget_imu_sensor.cpp) ament_target_dependencies( ${PROJECT_NAME}_test_phidget_imu_sensor hardware_interface rclcpp - husarion_ugv_utils panther_msgs phidgets_api) + husarion_ugv_utils husarion_ugv_msg phidgets_api) target_link_libraries(${PROJECT_NAME}_test_phidget_imu_sensor ${PROJECT_NAME} phidgets_spatial_parameters) @@ -118,7 +118,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_data_converters - panther_msgs husarion_ugv_utils) + husarion_ugv_msg husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_data_converters PkgConfig::LIBLELY_COAPP) @@ -131,7 +131,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_canopen_manager rclcpp - panther_msgs husarion_ugv_utils) + husarion_ugv_msg husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_canopen_manager PkgConfig::LIBLELY_COAPP) @@ -146,7 +146,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_driver rclcpp - panther_msgs husarion_ugv_utils) + husarion_ugv_msg husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_driver PkgConfig::LIBLELY_COAPP) @@ -163,7 +163,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_robot_driver rclcpp - panther_msgs husarion_ugv_utils) + husarion_ugv_msg husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_robot_driver PkgConfig::LIBLELY_COAPP) @@ -181,7 +181,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_lynx_robot_driver rclcpp - panther_msgs husarion_ugv_utils) + husarion_ugv_msg husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_lynx_robot_driver PkgConfig::LIBLELY_COAPP) @@ -199,7 +199,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_panther_robot_driver rclcpp - panther_msgs husarion_ugv_utils) + husarion_ugv_msg husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_panther_robot_driver PkgConfig::LIBLELY_COAPP) @@ -228,7 +228,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_system_ros_interface diagnostic_updater rclcpp - panther_msgs + husarion_ugv_msg husarion_ugv_utils realtime_tools std_srvs) @@ -256,7 +256,7 @@ if(BUILD_TESTING) diagnostic_updater hardware_interface rclcpp - panther_msgs + husarion_ugv_msg husarion_ugv_utils std_msgs std_srvs) @@ -289,7 +289,7 @@ if(BUILD_TESTING) diagnostic_updater hardware_interface rclcpp - panther_msgs + husarion_ugv_msg husarion_ugv_utils std_msgs std_srvs) @@ -323,7 +323,7 @@ if(BUILD_TESTING) diagnostic_updater hardware_interface rclcpp - panther_msgs + husarion_ugv_msg husarion_ugv_utils std_msgs std_srvs) diff --git a/husarion_ugv_hardware_interfaces/README.md b/husarion_ugv_hardware_interfaces/README.md index 980b93675..a34b865a3 100644 --- a/husarion_ugv_hardware_interfaces/README.md +++ b/husarion_ugv_hardware_interfaces/README.md @@ -14,8 +14,8 @@ Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: System diagnostic messages. - `hardware/e_stop` [*std_msgs/Bool*]: Current E-stop state. -- `hardware/io_state` [*panther_msgs/IOState*]: Current IO state. -- `hardware/robot_driver_state` [*panther_msgs/RobotDriverState*]: Current motor controllers' state and error flags. +- `hardware/io_state` [*husarion_ugv_msg/IOState*]: Current IO state. +- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: Current motor controllers' state and error flags. #### Service Servers diff --git a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp index ba3649db7..81cdf7878 100644 --- a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp @@ -21,9 +21,9 @@ #include #include -#include "panther_msgs/msg/fault_flag.hpp" -#include "panther_msgs/msg/runtime_error.hpp" -#include "panther_msgs/msg/script_flag.hpp" +#include "husarion_ugv_msg/msg/fault_flag.hpp" +#include "husarion_ugv_msg/msg/runtime_error.hpp" +#include "husarion_ugv_msg/msg/script_flag.hpp" #include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp" #include "husarion_ugv_hardware_interfaces/utils.hpp" @@ -124,7 +124,7 @@ class FaultFlag : public FlagError { public: FaultFlag(); - panther_msgs::msg::FaultFlag GetMessage() const; + husarion_ugv_msg::msg::FaultFlag GetMessage() const; std::map GetErrorMap() const; }; @@ -132,7 +132,7 @@ class ScriptFlag : public FlagError { public: ScriptFlag(); - panther_msgs::msg::ScriptFlag GetMessage() const; + husarion_ugv_msg::msg::ScriptFlag GetMessage() const; std::map GetErrorMap() const; }; @@ -140,7 +140,7 @@ class RuntimeError : public FlagError { public: RuntimeError(); - panther_msgs::msg::RuntimeError GetMessage() const; + husarion_ugv_msg::msg::RuntimeError GetMessage() const; std::map GetErrorMap() const; }; diff --git a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp index 4b813e17b..48a1abf8e 100644 --- a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp @@ -30,9 +30,9 @@ #include #include -#include "panther_msgs/msg/driver_state_named.hpp" -#include "panther_msgs/msg/io_state.hpp" -#include "panther_msgs/msg/robot_driver_state.hpp" +#include "husarion_ugv_msg/msg/driver_state_named.hpp" +#include "husarion_ugv_msg/msg/io_state.hpp" +#include "husarion_ugv_msg/msg/robot_driver_state.hpp" #include "husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_controller.hpp" #include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp" @@ -43,9 +43,9 @@ namespace husarion_ugv_hardware_interfaces { using BoolMsg = std_msgs::msg::Bool; -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; -using IOStateMsg = panther_msgs::msg::IOState; -using DriverStateNamedMsg = panther_msgs::msg::DriverStateNamed; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using IOStateMsg = husarion_ugv_msg::msg::IOState; +using DriverStateNamedMsg = husarion_ugv_msg::msg::DriverStateNamed; using SetBoolSrv = std_srvs::srv::SetBool; using TriggerSrv = std_srvs::srv::Trigger; diff --git a/husarion_ugv_hardware_interfaces/package.xml b/husarion_ugv_hardware_interfaces/package.xml index 90798d569..b45a4d6ff 100644 --- a/husarion_ugv_hardware_interfaces/package.xml +++ b/husarion_ugv_hardware_interfaces/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues @@ -31,9 +31,9 @@ generate_parameter_library geometry_msgs hardware_interface + husarion_ugv_msg husarion_ugv_utils imu_filter_madgwick - panther_msgs phidgets_api rclcpp rclcpp_lifecycle diff --git a/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp b/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp index e68902e31..6f3974c97 100644 --- a/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp +++ b/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp @@ -110,9 +110,9 @@ FaultFlag::FaultFlag() { } -panther_msgs::msg::FaultFlag FaultFlag::GetMessage() const +husarion_ugv_msg::msg::FaultFlag FaultFlag::GetMessage() const { - panther_msgs::msg::FaultFlag fault_flags_msg; + husarion_ugv_msg::msg::FaultFlag fault_flags_msg; fault_flags_msg.overheat = flags_.test(0); fault_flags_msg.overvoltage = flags_.test(1); @@ -137,9 +137,9 @@ std::map FaultFlag::GetErrorMap() const ScriptFlag::ScriptFlag() : FlagError({"loop_error", "encoder_disconnected", "amp_limiter"}) {} -panther_msgs::msg::ScriptFlag ScriptFlag::GetMessage() const +husarion_ugv_msg::msg::ScriptFlag ScriptFlag::GetMessage() const { - panther_msgs::msg::ScriptFlag script_flags_msg; + husarion_ugv_msg::msg::ScriptFlag script_flags_msg; script_flags_msg.loop_error = flags_.test(0); script_flags_msg.encoder_disconnected = flags_.test(1); @@ -178,9 +178,9 @@ RuntimeError::RuntimeError() { } -panther_msgs::msg::RuntimeError RuntimeError::GetMessage() const +husarion_ugv_msg::msg::RuntimeError RuntimeError::GetMessage() const { - panther_msgs::msg::RuntimeError runtime_errors_msg; + husarion_ugv_msg::msg::RuntimeError runtime_errors_msg; runtime_errors_msg.amps_limit_active = flags_.test(0); runtime_errors_msg.motor_stall = flags_.test(1); diff --git a/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp b/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp index 6eecd75e6..7f40f6c78 100644 --- a/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp +++ b/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp @@ -24,7 +24,7 @@ #include "utils/test_constants.hpp" void TestFaultFlagMsg( - const panther_msgs::msg::FaultFlag & msg, const std::vector & expected_values) + const husarion_ugv_msg::msg::FaultFlag & msg, const std::vector & expected_values) { if (expected_values.size() != 8) { throw std::runtime_error("Wrong size of expected_values in TestFaultFlagMsg"); @@ -41,7 +41,7 @@ void TestFaultFlagMsg( } void TestScriptFlagMsg( - const panther_msgs::msg::ScriptFlag & msg, const std::vector & expected_values) + const husarion_ugv_msg::msg::ScriptFlag & msg, const std::vector & expected_values) { if (expected_values.size() != 3) { throw std::runtime_error("Wrong size of expected_values in TestScriptFlagMsg"); @@ -53,7 +53,7 @@ void TestScriptFlagMsg( } void TestRuntimeErrorMsg( - const panther_msgs::msg::RuntimeError & msg, const std::vector & expected_values) + const husarion_ugv_msg::msg::RuntimeError & msg, const std::vector & expected_values) { if (expected_values.size() != 7) { throw std::runtime_error("Wrong size of expected_values in TestFaultFlagMsg"); diff --git a/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp b/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp index 6e3d15a11..271215c38 100644 --- a/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp +++ b/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp @@ -26,7 +26,7 @@ #include "utils/test_constants.hpp" -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; class SystemROSInterfaceWrapper : public husarion_ugv_hardware_interfaces::SystemROSInterface { diff --git a/husarion_ugv_lights/CMakeLists.txt b/husarion_ugv_lights/CMakeLists.txt index 3fc9de635..c8b06b3c9 100644 --- a/husarion_ugv_lights/CMakeLists.txt +++ b/husarion_ugv_lights/CMakeLists.txt @@ -9,7 +9,7 @@ set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater image_transport - panther_msgs + husarion_ugv_msg husarion_ugv_utils pluginlib rclcpp @@ -37,7 +37,7 @@ ament_target_dependencies( lights_driver_node_component diagnostic_updater image_transport - panther_msgs + husarion_ugv_msg rclcpp rclcpp_components sensor_msgs @@ -50,7 +50,7 @@ add_library( src/led_components/led_animations_queue.cpp) ament_target_dependencies( lights_controller_node_component - panther_msgs + husarion_ugv_msg husarion_ugv_utils pluginlib rclcpp diff --git a/husarion_ugv_lights/CONFIGURATION.md b/husarion_ugv_lights/CONFIGURATION.md index 986aba94c..5e3f31d4c 100644 --- a/husarion_ugv_lights/CONFIGURATION.md +++ b/husarion_ugv_lights/CONFIGURATION.md @@ -158,7 +158,7 @@ ros2 launch husarion_ugv_bringup bringup.launch user_animations_file:=/my_awesom Test new animations: ```bash -ros2 service call /lights/set_animation panther_msgs/srv/SetLEDAnimation "{animation: {id: 0, param: ''}, repeating: true}" +ros2 service call /lights/set_animation husarion_ugv_msg/srv/SetLEDAnimation "{animation: {id: 0, param: ''}, repeating: true}" ``` ## Defining a Custom Animation Type diff --git a/husarion_ugv_lights/README.md b/husarion_ugv_lights/README.md index 50a8c4e69..124f10550 100644 --- a/husarion_ugv_lights/README.md +++ b/husarion_ugv_lights/README.md @@ -26,7 +26,7 @@ This node is of type rclcpp_components is responsible for processing animations #### Service Servers -- `lights/set_animation` [*panther_msgs/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. +- `lights/set_animation` [*husarion_ugv_msg/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. #### Parameters @@ -49,7 +49,7 @@ This node is of type rclcpp_components is responsible for displaying frames on t #### Service Servers -- `lights/set_brightness` [*panther_msgs/SetLEDBrightness*]: Allows setting global LED brightness, value ranges from **0.0** to **1.0**. +- `lights/set_brightness` [*husarion_ugv_msg/SetLEDBrightness*]: Allows setting global LED brightness, value ranges from **0.0** to **1.0**. #### Service Clients diff --git a/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp b/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp index fc7b61cc6..2af12c820 100644 --- a/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp +++ b/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp @@ -25,7 +25,7 @@ #include "sensor_msgs/msg/image.hpp" -#include "panther_msgs/srv/set_led_animation.hpp" +#include "husarion_ugv_msg/srv/set_led_animation.hpp" #include "husarion_ugv_lights/animation/animation.hpp" #include "husarion_ugv_lights/led_components/led_animations_queue.hpp" @@ -36,7 +36,7 @@ namespace husarion_ugv_lights { using ImageMsg = sensor_msgs::msg::Image; -using SetLEDAnimationSrv = panther_msgs::srv::SetLEDAnimation; +using SetLEDAnimationSrv = husarion_ugv_msg::srv::SetLEDAnimation; class LightsControllerNode : public rclcpp::Node { diff --git a/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp b/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp index 0a5de4ae7..70107f621 100644 --- a/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp +++ b/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp @@ -24,7 +24,7 @@ #include "sensor_msgs/msg/image.hpp" #include "std_srvs/srv/set_bool.hpp" -#include "panther_msgs/srv/set_led_brightness.hpp" +#include "husarion_ugv_msg/srv/set_led_brightness.hpp" #include "husarion_ugv_lights/apa102.hpp" @@ -33,7 +33,7 @@ namespace husarion_ugv_lights using ImageMsg = sensor_msgs::msg::Image; using SetBoolSrv = std_srvs::srv::SetBool; -using SetLEDBrightnessSrv = panther_msgs::srv::SetLEDBrightness; +using SetLEDBrightnessSrv = husarion_ugv_msg::srv::SetLEDBrightness; /** * @brief Class for controlling APA102 LEDs based on a ROS Image topic. diff --git a/husarion_ugv_lights/package.xml b/husarion_ugv_lights/package.xml index 8e68c10c8..99c671046 100644 --- a/husarion_ugv_lights/package.xml +++ b/husarion_ugv_lights/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues @@ -17,10 +17,10 @@ ament_cmake diagnostic_updater + husarion_ugv_msg husarion_ugv_utils image_transport libpng-dev - panther_msgs pluginlib rclcpp rclcpp_components diff --git a/husarion_ugv_lights/src/lights_controller_node.cpp b/husarion_ugv_lights/src/lights_controller_node.cpp index b54cf25df..1092f0ba0 100644 --- a/husarion_ugv_lights/src/lights_controller_node.cpp +++ b/husarion_ugv_lights/src/lights_controller_node.cpp @@ -29,7 +29,7 @@ #include "sensor_msgs/msg/image.hpp" -#include "panther_msgs/srv/set_led_animation.hpp" +#include "husarion_ugv_msg/srv/set_led_animation.hpp" #include "husarion_ugv_lights/led_components/led_animations_queue.hpp" #include "husarion_ugv_lights/led_components/led_panel.hpp" diff --git a/husarion_ugv_lights/src/lights_driver_node.cpp b/husarion_ugv_lights/src/lights_driver_node.cpp index 62e892366..880811a5e 100644 --- a/husarion_ugv_lights/src/lights_driver_node.cpp +++ b/husarion_ugv_lights/src/lights_driver_node.cpp @@ -29,7 +29,7 @@ #include "sensor_msgs/msg/image.hpp" #include "std_srvs/srv/set_bool.hpp" -#include "panther_msgs/srv/set_led_brightness.hpp" +#include "husarion_ugv_msg/srv/set_led_brightness.hpp" #include "husarion_ugv_lights/apa102.hpp" diff --git a/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py b/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py index 906adb4be..4aaa17251 100644 --- a/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py +++ b/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py @@ -28,11 +28,12 @@ from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare from launch_testing_ros import WaitForTopics -from panther_msgs.msg import LEDAnimation -from panther_msgs.srv import SetLEDAnimation from sensor_msgs.msg import Image from std_srvs.srv import SetBool +from husarion_ugv_msg.msg import LEDAnimation +from husarion_ugv_msg.srv import SetLEDAnimation + def generate_test_description(): diff --git a/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp b/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp index 91fcc0c12..5a941e51a 100644 --- a/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp +++ b/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp @@ -23,7 +23,7 @@ #include #include -#include "panther_msgs/srv/set_led_brightness.hpp" +#include "husarion_ugv_msg/srv/set_led_brightness.hpp" #include "husarion_ugv_lights/apa102.hpp" #include "husarion_ugv_lights/lights_driver_node.hpp" @@ -31,7 +31,7 @@ using ImageMsg = sensor_msgs::msg::Image; using SetBoolSrv = std_srvs::srv::SetBool; -using SetLEDBrightnessSrv = panther_msgs::srv::SetLEDBrightness; +using SetLEDBrightnessSrv = husarion_ugv_msg::srv::SetLEDBrightness; class MockAPA102 : public husarion_ugv_lights::APA102Interface { diff --git a/husarion_ugv_localization/package.xml b/husarion_ugv_localization/package.xml index bc7cd0d51..878177e09 100644 --- a/husarion_ugv_localization/package.xml +++ b/husarion_ugv_localization/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues diff --git a/husarion_ugv_manager/CMakeLists.txt b/husarion_ugv_manager/CMakeLists.txt index 292866117..04783438d 100644 --- a/husarion_ugv_manager/CMakeLists.txt +++ b/husarion_ugv_manager/CMakeLists.txt @@ -11,7 +11,7 @@ set(PACKAGE_DEPENDENCIES behaviortree_cpp behaviortree_ros2 libssh - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp rclcpp_action @@ -66,7 +66,7 @@ add_executable( ament_target_dependencies( safety_manager_node behaviortree_ros2 - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs @@ -79,7 +79,7 @@ add_executable( ament_target_dependencies( lights_manager_node behaviortree_ros2 - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs @@ -192,7 +192,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_lights_manager_node behaviortree_cpp behaviortree_ros2 - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs @@ -210,7 +210,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_lights_behavior_tree behaviortree_cpp behaviortree_ros2 - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs @@ -227,7 +227,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_safety_manager_node behaviortree_cpp behaviortree_ros2 - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs @@ -245,7 +245,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_safety_behavior_tree behaviortree_cpp behaviortree_ros2 - panther_msgs + husarion_ugv_msg husarion_ugv_utils rclcpp sensor_msgs diff --git a/husarion_ugv_manager/CONFIGURATION.md b/husarion_ugv_manager/CONFIGURATION.md index adc2337aa..cfe40bd8d 100644 --- a/husarion_ugv_manager/CONFIGURATION.md +++ b/husarion_ugv_manager/CONFIGURATION.md @@ -67,7 +67,7 @@ For a BehaviorTree project to work correctly, it must contain a tree with correc - `CallSetBoolService` - allows calling the standard **std_srvs/SetBool** ROS service. Provided ports are: - `data` [*input*, *bool*, default: **None**]: service data - **true** or **false** value. - `service_name` [*input*, *string*, default: **None**]: ROS service name. -- `CallSetLedAnimationService` - allows calling custom type **panther_msgs/SetLEDAnimation** ROS service. The provided ports are: +- `CallSetLedAnimationService` - allows calling custom type **husarion_ugv_msg/SetLEDAnimation** ROS service. The provided ports are: - `id` [*input*, *unsigned*, default: **None**]: animation ID. - `param` [*input*, *string*, default: **None**]: optional parameter passed to animation. - `repeating` [*input*, *bool*, default: **false**]: indicates if the animation should repeat. @@ -118,16 +118,16 @@ Default constant blackboard entries: - `CRITICAL_BATTERY_THRESHOLD_PERCENT` [*float*, default: **0.1**]: refers to `critical_battery_threshold_percent` ROS parameter. - `LOW_BATTERY_ANIM_PERIOD` [*float*, default: **30.0**]: refers to `low_battery_anim_period` ROS parameter. - `LOW_BATTERY_THRESHOLD_PERCENT` [*float*, default: **0.4**]: refers to `low_battery_threshold_percent` ROS parameter. -- `E_STOP_ANIM_ID` [*unsigned*, value: **0**]: animation ID constant obtained from `panther_msgs::LEDAnimation::E_STOP`. -- `READY_ANIM_ID` [*unsigned*, value: **1**]: animation ID constant obtained from `panther_msgs::LEDAnimation::READY`. -- `ERROR_ANIM_ID` [*unsigned*, value: **2**]: animation ID constant obtained from `panther_msgs::LEDAnimation::ERROR`. -- `MANUAL_ACTION_ANIM_ID` [*unsigned*, value: **3**]: animation ID constant obtained from `panther_msgs::LEDAnimation::MANUAL_ACTION`. -- `AUTONOMOUS_ACTION_ANIM_ID` [*unsigned*, value: **4**]: animation ID constant obtained from `panther_msgs::LEDAnimation::AUTONOMOUS_ACTION`. -- `GOAL_ACHIEVED_ANIM_ID` [*unsigned*, value: **5**]: animation ID constant obtained from `panther_msgs::LEDAnimation::GOAL_ACHIEVED`. -- `LOW_BATTERY_ANIM_ID` [*unsigned*, value: **6**]: animation ID constant obtained from `panther_msgs::LEDAnimation::LOW_BATTERY`. -- `CRITICAL_BATTERY_ANIM_ID` [*unsigned*, value: **7**]: animation ID constant obtained from `panther_msgs::LEDAnimation::CRITICAL_BATTERY`. -- `BATTERY_STATE_ANIM_ID` [*unsigned*, value: **8**]: animation ID constant obtained from `panther_msgs::LEDAnimation::BATTERY_STATE`. -- `CHARGING_BATTERY_ANIM_ID` [*unsigned*, value: **9**]: animation ID constant obtained from `panther_msgs::LEDAnimation::CHARGING_BATTERY`. +- `E_STOP_ANIM_ID` [*unsigned*, value: **0**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::E_STOP`. +- `READY_ANIM_ID` [*unsigned*, value: **1**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::READY`. +- `ERROR_ANIM_ID` [*unsigned*, value: **2**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::ERROR`. +- `MANUAL_ACTION_ANIM_ID` [*unsigned*, value: **3**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::MANUAL_ACTION`. +- `AUTONOMOUS_ACTION_ANIM_ID` [*unsigned*, value: **4**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::AUTONOMOUS_ACTION`. +- `GOAL_ACHIEVED_ANIM_ID` [*unsigned*, value: **5**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::GOAL_ACHIEVED`. +- `LOW_BATTERY_ANIM_ID` [*unsigned*, value: **6**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::LOW_BATTERY`. +- `CRITICAL_BATTERY_ANIM_ID` [*unsigned*, value: **7**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::CRITICAL_BATTERY`. +- `BATTERY_STATE_ANIM_ID` [*unsigned*, value: **8**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::BATTERY_STATE`. +- `CHARGING_BATTERY_ANIM_ID` [*unsigned*, value: **9**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::CHARGING_BATTERY`. - `POWER_SUPPLY_STATUS_UNKNOWN` [*unsigned*, value: **0**]: power supply status constant obtained from `sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN`. - `POWER_SUPPLY_STATUS_CHARGING` [*unsigned*, value: **1**]: power supply status constant obtained from `sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_CHARGING`. - `POWER_SUPPLY_STATUS_DISCHARGING` [*unsigned*, value: **2**]: power supply status constant obtained from `sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING`. diff --git a/husarion_ugv_manager/README.md b/husarion_ugv_manager/README.md index b8a9795f9..b58cc32e3 100644 --- a/husarion_ugv_manager/README.md +++ b/husarion_ugv_manager/README.md @@ -32,7 +32,7 @@ Node responsible for managing Bumper Lights animation scheduling. #### Service Clients (for Default Trees) -- `~/lights/set_animation` [*panther_msgs/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. +- `~/lights/set_animation` [*husarion_ugv_msg/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. #### Parameters @@ -57,9 +57,9 @@ Node responsible for managing safety features, and software shutdown of componen - `battery/battery_status` [*sensor_msgs/BatteryState*]: State of the internal Battery. - `hardware/e_stop` [*std_msgs/Bool*]: State of emergency stop. -- `hardware/io_state` [*panther_msgs/IOState*]: State of IO pins. -- `hardware/robot_driver_state` [*panther_msgs/RobotDriverState*]: State of motor controllers. -- `system_status` [*panther_msgs/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. +- `hardware/io_state` [*husarion_ugv_msg/IOState*]: State of IO pins. +- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: State of motor controllers. +- `system_status` [*husarion_ugv_msg/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. #### Service Clients (for Default Trees) diff --git a/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp b/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp index 6fd54433e..c2d345933 100644 --- a/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp +++ b/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp @@ -24,7 +24,7 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "panther_msgs/msg/led_animation.hpp" +#include "husarion_ugv_msg/msg/led_animation.hpp" #include "husarion_ugv_utils/moving_average.hpp" @@ -35,7 +35,7 @@ namespace husarion_ugv_manager using BatteryStateMsg = sensor_msgs::msg::BatteryState; using BoolMsg = std_msgs::msg::Bool; -using LEDAnimationMsg = panther_msgs::msg::LEDAnimation; +using LEDAnimationMsg = husarion_ugv_msg::msg::LEDAnimation; /** * @brief This class is responsible for creating a BehaviorTree responsible for lights management, diff --git a/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp b/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp index 4fa2f8f83..9ce9ccea8 100644 --- a/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp +++ b/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp @@ -20,17 +20,17 @@ #include "behaviortree_ros2/bt_service_node.hpp" #include "rclcpp/rclcpp.hpp" -#include "panther_msgs/srv/set_led_animation.hpp" +#include "husarion_ugv_msg/srv/set_led_animation.hpp" namespace husarion_ugv_manager { -class CallSetLedAnimationService : public BT::RosServiceNode +class CallSetLedAnimationService : public BT::RosServiceNode { public: CallSetLedAnimationService( const std::string & name, const BT::NodeConfig & conf, const BT::RosNodeParams & params) - : BT::RosServiceNode(name, conf, params) + : BT::RosServiceNode(name, conf, params) { } diff --git a/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp b/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp index 51dcb3e2a..dcd28a6db 100644 --- a/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp +++ b/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp @@ -25,9 +25,9 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "panther_msgs/msg/io_state.hpp" -#include "panther_msgs/msg/robot_driver_state.hpp" -#include "panther_msgs/msg/system_status.hpp" +#include "husarion_ugv_msg/msg/io_state.hpp" +#include "husarion_ugv_msg/msg/robot_driver_state.hpp" +#include "husarion_ugv_msg/msg/system_status.hpp" #include "husarion_ugv_utils/moving_average.hpp" @@ -38,9 +38,9 @@ namespace husarion_ugv_manager using BatteryStateMsg = sensor_msgs::msg::BatteryState; using BoolMsg = std_msgs::msg::Bool; -using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; -using IOStateMsg = panther_msgs::msg::IOState; -using SystemStatusMsg = panther_msgs::msg::SystemStatus; +using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using IOStateMsg = husarion_ugv_msg::msg::IOState; +using SystemStatusMsg = husarion_ugv_msg::msg::SystemStatus; /** * @brief This class is responsible for creating a BehaviorTrees responsible for safety and shutdown diff --git a/husarion_ugv_manager/package.xml b/husarion_ugv_manager/package.xml index 3b5688d0e..5c110f73c 100644 --- a/husarion_ugv_manager/package.xml +++ b/husarion_ugv_manager/package.xml @@ -8,7 +8,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues @@ -19,11 +19,11 @@ behaviortree_cpp behaviortree_ros2 + husarion_ugv_msg husarion_ugv_utils iputils-ping libboost-dev libssh-dev - panther_msgs rclcpp rclcpp_action std_srvs diff --git a/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp b/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp index 1708ef7d1..a6717981c 100644 --- a/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp +++ b/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp @@ -28,14 +28,14 @@ class TestCallSetLedAnimationService { public: void ServiceCallback( - const panther_msgs::srv::SetLEDAnimation::Request::SharedPtr request, - panther_msgs::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, + const husarion_ugv_msg::srv::SetLEDAnimation::Request::SharedPtr request, + husarion_ugv_msg::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, const std::size_t id, const bool repeating); }; void TestCallSetLedAnimationService::ServiceCallback( - const panther_msgs::srv::SetLEDAnimation::Request::SharedPtr request, - panther_msgs::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, + const husarion_ugv_msg::srv::SetLEDAnimation::Request::SharedPtr request, + husarion_ugv_msg::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, const std::size_t id, const bool repeating) { response->message = success ? "Successfully callback pass!" : "Failed callback pass!"; @@ -98,7 +98,7 @@ TEST_F(TestCallSetLedAnimationService, GoodSetLedAnimationCallServiceSuccessWith CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using panther_msgs::srv::SetLEDAnimation; + using husarion_ugv_msg::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( @@ -121,7 +121,7 @@ TEST_F(TestCallSetLedAnimationService, GoodSetLedAnimationCallServiceSuccessWith CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using panther_msgs::srv::SetLEDAnimation; + using husarion_ugv_msg::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( @@ -144,7 +144,7 @@ TEST_F(TestCallSetLedAnimationService, GoodSetLedAnimationCallServiceSuccessWith CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using panther_msgs::srv::SetLEDAnimation; + using husarion_ugv_msg::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( @@ -167,7 +167,7 @@ TEST_F(TestCallSetLedAnimationService, WrongSetLedAnimationCallServiceFailure) CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using panther_msgs::srv::SetLEDAnimation; + using husarion_ugv_msg::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( diff --git a/husarion_ugv_manager/test/test_lights_behavior_tree.cpp b/husarion_ugv_manager/test/test_lights_behavior_tree.cpp index 4a9f342d5..de0d1c4d6 100644 --- a/husarion_ugv_manager/test/test_lights_behavior_tree.cpp +++ b/husarion_ugv_manager/test/test_lights_behavior_tree.cpp @@ -28,16 +28,16 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "panther_msgs/msg/led_animation.hpp" -#include "panther_msgs/srv/set_led_animation.hpp" +#include "husarion_ugv_msg/msg/led_animation.hpp" +#include "husarion_ugv_msg/srv/set_led_animation.hpp" #include #include using BoolMsg = std_msgs::msg::Bool; using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using SetLEDAnimationSrv = panther_msgs::srv::SetLEDAnimation; -using LEDAnimationMsg = panther_msgs::msg::LEDAnimation; +using SetLEDAnimationSrv = husarion_ugv_msg::srv::SetLEDAnimation; +using LEDAnimationMsg = husarion_ugv_msg::msg::LEDAnimation; class LightsManagerNodeWrapper : public husarion_ugv_manager::LightsManagerNode { diff --git a/husarion_ugv_manager/test/test_safety_behavior_tree.cpp b/husarion_ugv_manager/test/test_safety_behavior_tree.cpp index 6f9540bfd..9ddb01668 100644 --- a/husarion_ugv_manager/test/test_safety_behavior_tree.cpp +++ b/husarion_ugv_manager/test/test_safety_behavior_tree.cpp @@ -30,16 +30,16 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" -#include "panther_msgs/msg/io_state.hpp" -#include "panther_msgs/msg/system_status.hpp" +#include "husarion_ugv_msg/msg/io_state.hpp" +#include "husarion_ugv_msg/msg/system_status.hpp" #include #include using BoolMsg = std_msgs::msg::Bool; using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using IOStateMsg = panther_msgs::msg::IOState; -using SystemStatusMsg = panther_msgs::msg::SystemStatus; +using IOStateMsg = husarion_ugv_msg::msg::IOState; +using SystemStatusMsg = husarion_ugv_msg::msg::SystemStatus; using SetBoolSrv = std_srvs::srv::SetBool; using TriggerSrv = std_srvs::srv::Trigger; diff --git a/husarion_ugv_manager/test/test_safety_manager_node.cpp b/husarion_ugv_manager/test/test_safety_manager_node.cpp index 036ccdfe6..62c144df4 100644 --- a/husarion_ugv_manager/test/test_safety_manager_node.cpp +++ b/husarion_ugv_manager/test/test_safety_manager_node.cpp @@ -194,10 +194,10 @@ TEST_F(TestSafetyManagerNode, DriverStateCBBlackboardUpdate) { const float expected_temp = 21.0; - panther_msgs::msg::DriverStateNamed driver_state; + husarion_ugv_msg::msg::DriverStateNamed driver_state; driver_state.state.temperature = expected_temp; - auto driver_state_msg = panther_msgs::msg::RobotDriverState(); + auto driver_state_msg = husarion_ugv_msg::msg::RobotDriverState(); driver_state_msg.driver_states.push_back(driver_state); husarion_ugv_utils::test_utils::PublishAndSpin( @@ -212,7 +212,7 @@ TEST_F(TestSafetyManagerNode, IOStateCBBlackboardUpdate) const bool expected_aux_state = true; const bool expected_fan_state = true; - auto io_state_msg = panther_msgs::msg::IOState(); + auto io_state_msg = husarion_ugv_msg::msg::IOState(); io_state_msg.aux_power = expected_aux_state; io_state_msg.fan = expected_fan_state; @@ -228,7 +228,7 @@ TEST_F(TestSafetyManagerNode, SystemStatusCBBlackboardUpdate) { const float expected_temp = 21.0; - auto system_status_msg = panther_msgs::msg::SystemStatus(); + auto system_status_msg = husarion_ugv_msg::msg::SystemStatus(); system_status_msg.cpu_temp = expected_temp; husarion_ugv_utils::test_utils::PublishAndSpin( diff --git a/husarion_ugv_manager/test/utils/plugin_test_utils.hpp b/husarion_ugv_manager/test/utils/plugin_test_utils.hpp index f9d4af87e..d323b9a01 100644 --- a/husarion_ugv_manager/test/utils/plugin_test_utils.hpp +++ b/husarion_ugv_manager/test/utils/plugin_test_utils.hpp @@ -30,7 +30,7 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" -#include "panther_msgs/srv/set_led_animation.hpp" +#include "husarion_ugv_msg/srv/set_led_animation.hpp" #include "husarion_ugv_manager/plugins/action/call_set_bool_service_node.hpp" #include "husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp" diff --git a/husarion_ugv_msg/CHANGELOG.rst b/husarion_ugv_msg/CHANGELOG.rst new file mode 100644 index 000000000..a0b420b63 --- /dev/null +++ b/husarion_ugv_msg/CHANGELOG.rst @@ -0,0 +1,95 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package panther_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.1.2 (2024-12-02) +------------------ + +2.1.1 (2024-09-05) +------------------ + +2.1.0 (2024-08-02) +------------------ +* Merge pull request `#76 `_ from husarion/hotfix-handle-can-timeout +* Rename can communication errors +* Add heartbeat timeout message attribute +* Merge pull request `#75 `_ from husarion/ros2-grant-permission +* Uncomment steps +* Test checking out +* Grant permission before main checkout +* Contributors: Jan brzyk, Paweł Irzyk, pawelirh + +2.0.4 (2024-06-28) +------------------ +* Bugfix: Grant permission and add warning in release workflow (`#71 `_) +* hotfix-allow-unshallow-copy +* Add ChargingStatus message (`#64 `_) +* Merge pull request `#63 `_ from husarion/ros2-update-iostate-msg +* Add led_control field +* Enable fetch full history - workflow (`#62 `_) +* Ros2 workflow bugfix update devel (`#61 `_) +* Contributors: Dawid Kmak, Paweł Irzyk, pawelirh + +2.0.3 (2024-06-06) +------------------ +* Ros2 improve release process (`#58 `_) +* Contributors: Paweł Irzyk + +2.0.2 (2024-06-05) +------------------ + +2.0.1 (2024-05-01) +------------------ +* Ros2 workflow missing arguments (`#49 `_) +* Ros2 handle boolean args (`#43 `_) +* Prevent unwanted PR (`#35 `_) +* Add PR body (`#33 `_) +* Update workflow (`#30 `_) +* Revert version in package.xml (`#29 `_) +* Ros2 automatize release process (`#25 `_) +* Merge pull request `#22 `_ from husarion/ros2-update-workflow +* Update setup-ros +* Merge pull request `#21 `_ from husarion/release-2.0.0-alpha +* Contributors: Jakub Delicat, Paweł Irzyk, Paweł Kowalski, rafal-gorecki + +2.0.0 (2024-03-29) +------------------ +* Merge pull request `#19 `_ from husarion/ros2-fix-typo + fix typo +* fix typo +* Merge pull request `#17 `_ from husarion/ros2-control + Ros2 control changes +* ros2_control PDO commands (`#18 `_) + * Add heatsink temperature + * Update error names + * Update timed out errors +* Merge branch 'ros2' into ros2-control + Conflicts: + msg/DriverState.msg + msg/MotorControllerState.msg + msg/MotorState.msg +* Refactor motor controller state msg - remove joint name and move runtime error +* Move can error to motorcontrollerstate +* Rename fields +* Add more information to driver state msg +* Merge pull request `#16 `_ from husarion/ros2-update-panther-msgs + ROS 2 update panther msgs +* Update services +* Update messages +* update package.xml +* add DriverState msg +* ROS2 devel (`#2 `_) + * Initial commit + * Initial commit + * Fix issue with no panther_msgs listing + * Change workflow name + * Change workflow file name + * Fix workflows folder name typo + * Change workflow name + * Reatach ROS2 workflow to ros2 branch + * Update package.xml + * Unwrap package folder + * Fixed email by adding .com in package.xml + Co-authored-by: Nicolas Duc <49471089+TopRamen1@users.noreply.github.com> +* Initial commit +* Contributors: Dawid, Dominik Nowak, Krzysztof Wojciechowski, Maciej Stępień, Paweł Kowalski diff --git a/husarion_ugv_msg/CMakeLists.txt b/husarion_ugv_msg/CMakeLists.txt new file mode 100644 index 000000000..ab71cbdeb --- /dev/null +++ b/husarion_ugv_msg/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 3.10.2) +project(husarion_ugv_msg) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(std_msgs REQUIRED) + +rosidl_generate_interfaces( + ${PROJECT_NAME} + "msg/ChargingStatus.msg" + "msg/DriverState.msg" + "msg/DriverStateNamed.msg" + "msg/FaultFlag.msg" + "msg/IOState.msg" + "msg/LEDAnimation.msg" + "msg/LEDAnimationQueue.msg" + "msg/LEDImageAnimation.msg" + "msg/RobotDriverState.msg" + "msg/RuntimeError.msg" + "msg/ScriptFlag.msg" + "msg/SystemStatus.msg" + "srv/SetLEDAnimation.srv" + "srv/SetLEDBrightness.srv" + "srv/SetLEDImageAnimation.srv" + DEPENDENCIES + std_msgs) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/husarion_ugv_msg/README.md b/husarion_ugv_msg/README.md new file mode 100644 index 000000000..a0ac941e1 --- /dev/null +++ b/husarion_ugv_msg/README.md @@ -0,0 +1,3 @@ +# husarion_ugv_msg + +Custom ROS messages and services for Panther robot. diff --git a/husarion_ugv_msg/msg/ChargingStatus.msg b/husarion_ugv_msg/msg/ChargingStatus.msg new file mode 100644 index 000000000..7d097f74e --- /dev/null +++ b/husarion_ugv_msg/msg/ChargingStatus.msg @@ -0,0 +1,13 @@ +# This message defines the battery charging process status + +# Charger types +uint8 UNKNOWN = 0 +uint8 WIRED = 1 +uint8 WIRELESS = 2 + +std_msgs/Header header +bool charging # True if battery is being charged +float32 current # Power supply total current (A) +float32 current_battery_1 # Power supply current (A) for battery 1 +float32 current_battery_2 # Power supply current (A) for battery 2 (NaN for single battery configuration) +uint8 charger_type # Determines the type of charger connection diff --git a/husarion_ugv_msg/msg/DriverState.msg b/husarion_ugv_msg/msg/DriverState.msg new file mode 100644 index 000000000..535a33cad --- /dev/null +++ b/husarion_ugv_msg/msg/DriverState.msg @@ -0,0 +1,14 @@ +float32 voltage +float32 current +float32 temperature +float32 heatsink_temperature + +husarion_ugv_msg/FaultFlag fault_flag +husarion_ugv_msg/ScriptFlag script_flag +husarion_ugv_msg/RuntimeError channel_1_motor_runtime_error +husarion_ugv_msg/RuntimeError channel_2_motor_runtime_error + +bool motor_states_data_timed_out +bool driver_state_data_timed_out +bool can_error +bool heartbeat_timeout diff --git a/husarion_ugv_msg/msg/DriverStateNamed.msg b/husarion_ugv_msg/msg/DriverStateNamed.msg new file mode 100644 index 000000000..6a3528b96 --- /dev/null +++ b/husarion_ugv_msg/msg/DriverStateNamed.msg @@ -0,0 +1,6 @@ +string NAME_DEFAULT = "default" +string NAME_FRONT = "front" +string NAME_REAR = "rear" + +string name +husarion_ugv_msg/DriverState state diff --git a/husarion_ugv_msg/msg/FaultFlag.msg b/husarion_ugv_msg/msg/FaultFlag.msg new file mode 100644 index 000000000..ccfa8ff99 --- /dev/null +++ b/husarion_ugv_msg/msg/FaultFlag.msg @@ -0,0 +1,8 @@ +bool overheat +bool overvoltage +bool undervoltage +bool short_circuit +bool emergency_stop +bool motor_or_sensor_setup_fault +bool mosfet_failure +bool default_config_loaded_at_startup diff --git a/husarion_ugv_msg/msg/IOState.msg b/husarion_ugv_msg/msg/IOState.msg new file mode 100644 index 000000000..1c10803d4 --- /dev/null +++ b/husarion_ugv_msg/msg/IOState.msg @@ -0,0 +1,8 @@ +bool aux_power +bool charger_connected +bool charger_enabled +bool digital_power +bool fan +bool led_control +bool motor_on +bool power_button diff --git a/husarion_ugv_msg/msg/LEDAnimation.msg b/husarion_ugv_msg/msg/LEDAnimation.msg new file mode 100644 index 000000000..2bd339fc5 --- /dev/null +++ b/husarion_ugv_msg/msg/LEDAnimation.msg @@ -0,0 +1,13 @@ +uint16 E_STOP = 0 +uint16 READY = 1 +uint16 ERROR = 2 +uint16 MANUAL_ACTION = 3 +uint16 AUTONOMOUS_ACTION = 4 +uint16 GOAL_ACHIEVED = 5 +uint16 LOW_BATTERY = 6 +uint16 CRITICAL_BATTERY = 7 +uint16 BATTERY_STATE = 8 +uint16 CHARGING_BATTERY = 9 + +uint16 id +string param diff --git a/husarion_ugv_msg/msg/LEDAnimationQueue.msg b/husarion_ugv_msg/msg/LEDAnimationQueue.msg new file mode 100644 index 000000000..9996f516e --- /dev/null +++ b/husarion_ugv_msg/msg/LEDAnimationQueue.msg @@ -0,0 +1 @@ +string[] queue diff --git a/husarion_ugv_msg/msg/LEDImageAnimation.msg b/husarion_ugv_msg/msg/LEDImageAnimation.msg new file mode 100644 index 000000000..fc1fde293 --- /dev/null +++ b/husarion_ugv_msg/msg/LEDImageAnimation.msg @@ -0,0 +1,5 @@ +string image +float32 duration +float32 brightness +uint8 repeat +uint32 color diff --git a/husarion_ugv_msg/msg/RobotDriverState.msg b/husarion_ugv_msg/msg/RobotDriverState.msg new file mode 100644 index 000000000..3be5deae8 --- /dev/null +++ b/husarion_ugv_msg/msg/RobotDriverState.msg @@ -0,0 +1,8 @@ +std_msgs/Header header + +husarion_ugv_msg/DriverStateNamed[] driver_states + +bool error +bool write_pdo_cmds_error +bool read_pdo_motor_states_error +bool read_pdo_driver_state_error diff --git a/husarion_ugv_msg/msg/RuntimeError.msg b/husarion_ugv_msg/msg/RuntimeError.msg new file mode 100644 index 000000000..459d9b275 --- /dev/null +++ b/husarion_ugv_msg/msg/RuntimeError.msg @@ -0,0 +1,7 @@ +bool amps_limit_active +bool motor_stall +bool loop_error +bool safety_stop_active +bool forward_limit_triggered +bool reverse_limit_triggered +bool amps_trigger_activated diff --git a/husarion_ugv_msg/msg/ScriptFlag.msg b/husarion_ugv_msg/msg/ScriptFlag.msg new file mode 100644 index 000000000..85d5ce469 --- /dev/null +++ b/husarion_ugv_msg/msg/ScriptFlag.msg @@ -0,0 +1,3 @@ +bool loop_error +bool encoder_disconnected +bool amp_limiter diff --git a/husarion_ugv_msg/msg/SystemStatus.msg b/husarion_ugv_msg/msg/SystemStatus.msg new file mode 100644 index 000000000..7a09023ba --- /dev/null +++ b/husarion_ugv_msg/msg/SystemStatus.msg @@ -0,0 +1,7 @@ +std_msgs/Header header + +float32[] cpu_percent +float32 cpu_temp +float32 avg_load_percent +float32 ram_usage_percent +float32 disc_usage_percent diff --git a/husarion_ugv_msg/package.xml b/husarion_ugv_msg/package.xml new file mode 100644 index 000000000..ae503181a --- /dev/null +++ b/husarion_ugv_msg/package.xml @@ -0,0 +1,29 @@ + + + + husarion_ugv_msg + 2.1.2 + Custom messages for Husarion UGV + Husarion + Apache License 2.0 + + https://husarion.com + https://github.com/husarion/panther_ros + https://github.com/husarion/panther_ros/issues + + Dawid Kmak + Krzysztof Wojciechowski + + ament_cmake + rosidl_default_generators + + builtin_interfaces + std_msgs + + rosidl_default_runtime + rosidl_interface_packages + + + ament_cmake + + diff --git a/husarion_ugv_msg/srv/SetLEDAnimation.srv b/husarion_ugv_msg/srv/SetLEDAnimation.srv new file mode 100644 index 000000000..7234925d4 --- /dev/null +++ b/husarion_ugv_msg/srv/SetLEDAnimation.srv @@ -0,0 +1,5 @@ +husarion_ugv_msg/LEDAnimation animation +bool repeating +--- +bool success +string message diff --git a/husarion_ugv_msg/srv/SetLEDBrightness.srv b/husarion_ugv_msg/srv/SetLEDBrightness.srv new file mode 100644 index 000000000..e7b83e801 --- /dev/null +++ b/husarion_ugv_msg/srv/SetLEDBrightness.srv @@ -0,0 +1,4 @@ +float32 data +--- +bool success +string message diff --git a/husarion_ugv_msg/srv/SetLEDImageAnimation.srv b/husarion_ugv_msg/srv/SetLEDImageAnimation.srv new file mode 100644 index 000000000..98474a614 --- /dev/null +++ b/husarion_ugv_msg/srv/SetLEDImageAnimation.srv @@ -0,0 +1,7 @@ +husarion_ugv_msg/LEDImageAnimation front +husarion_ugv_msg/LEDImageAnimation rear +bool interrupting +bool repeating +--- +bool success +string message diff --git a/husarion_ugv_utils/package.xml b/husarion_ugv_utils/package.xml index 9c5c4fd98..d0ceaad94 100644 --- a/husarion_ugv_utils/package.xml +++ b/husarion_ugv_utils/package.xml @@ -7,7 +7,7 @@ Husarion Apache License 2.0 - https://husarion.com/ + https://husarion.com https://github.com/husarion/panther_ros https://github.com/husarion/panther_ros/issues From d408f44d3fc319c89f209d6a4a7cec4a4499c6c0 Mon Sep 17 00:00:00 2001 From: rafal-gorecki Date: Wed, 11 Dec 2024 15:23:42 +0100 Subject: [PATCH 2/3] husarion_ugv_msg -> husarion_ugv_msgs --- ROS_API.md | 12 +++++----- husarion_ugv_battery/CMakeLists.txt | 8 +++---- husarion_ugv_battery/README.md | 6 ++--- .../husarion_ugv_battery/battery/battery.hpp | 4 ++-- .../battery/roboteq_battery.hpp | 8 +++---- .../battery_driver_node.hpp | 4 ++-- .../battery_publisher/battery_publisher.hpp | 8 +++---- husarion_ugv_battery/package.xml | 2 +- .../test/battery/test_adc_battery.cpp | 4 ++-- .../test/battery/test_battery.cpp | 4 ++-- .../test/battery/test_roboteq_battery.cpp | 10 ++++---- .../test_battery_publisher.cpp | 4 ++-- .../test_dual_battery_publisher.cpp | 4 ++-- .../test/test_battery_driver_node_roboteq.cpp | 4 ++-- .../test/utils/test_battery_driver_node.hpp | 8 +++---- husarion_ugv_diagnostics/CMakeLists.txt | 2 +- husarion_ugv_diagnostics/README.md | 2 +- .../system_monitor_node.hpp | 6 ++--- husarion_ugv_diagnostics/package.xml | 2 +- .../src/system_monitor_node.cpp | 8 +++---- .../integration/system_monitor_node.test.py | 2 +- .../test/unit/test_system_monitor_node.cpp | 2 +- .../CMakeLists.txt | 24 +++++++++---------- husarion_ugv_hardware_interfaces/README.md | 4 ++-- .../robot_driver/roboteq_data_converters.hpp | 12 +++++----- .../robot_system/system_ros_interface.hpp | 12 +++++----- husarion_ugv_hardware_interfaces/package.xml | 2 +- .../robot_driver/roboteq_data_converters.cpp | 12 +++++----- .../test_roboteq_data_converters.cpp | 6 ++--- .../test_system_ros_interface.cpp | 2 +- husarion_ugv_lights/CMakeLists.txt | 6 ++--- husarion_ugv_lights/CONFIGURATION.md | 2 +- husarion_ugv_lights/README.md | 4 ++-- .../lights_controller_node.hpp | 4 ++-- .../lights_driver_node.hpp | 4 ++-- husarion_ugv_lights/package.xml | 2 +- .../src/lights_controller_node.cpp | 2 +- .../src/lights_driver_node.cpp | 2 +- .../integration/husarion_ugv_lights.test.py | 4 ++-- .../test/unit/test_lights_driver_node.cpp | 4 ++-- husarion_ugv_manager/CMakeLists.txt | 14 +++++------ husarion_ugv_manager/CONFIGURATION.md | 22 ++++++++--------- husarion_ugv_manager/README.md | 8 +++---- .../lights_manager_node.hpp | 4 ++-- .../call_set_led_animation_service_node.hpp | 7 +++--- .../safety_manager_node.hpp | 12 +++++----- husarion_ugv_manager/package.xml | 2 +- ...st_call_set_led_animation_service_node.cpp | 16 ++++++------- .../test/test_lights_behavior_tree.cpp | 8 +++---- .../test/test_safety_behavior_tree.cpp | 8 +++---- .../test/test_safety_manager_node.cpp | 8 +++---- .../test/utils/plugin_test_utils.hpp | 2 +- husarion_ugv_msg/msg/DriverState.msg | 14 ----------- husarion_ugv_msg/srv/SetLEDImageAnimation.srv | 7 ------ .../CHANGELOG.rst | 0 .../CMakeLists.txt | 2 +- .../README.md | 2 +- .../msg/ChargingStatus.msg | 0 husarion_ugv_msgs/msg/DriverState.msg | 14 +++++++++++ .../msg/DriverStateNamed.msg | 2 +- .../msg/FaultFlag.msg | 0 .../msg/IOState.msg | 0 .../msg/LEDAnimation.msg | 0 .../msg/LEDAnimationQueue.msg | 0 .../msg/LEDImageAnimation.msg | 0 .../msg/RobotDriverState.msg | 2 +- .../msg/RuntimeError.msg | 0 .../msg/ScriptFlag.msg | 0 .../msg/SystemStatus.msg | 0 .../package.xml | 2 +- .../srv/SetLEDAnimation.srv | 2 +- .../srv/SetLEDBrightness.srv | 0 .../srv/SetLEDImageAnimation.srv | 7 ++++++ 73 files changed, 194 insertions(+), 193 deletions(-) delete mode 100644 husarion_ugv_msg/msg/DriverState.msg delete mode 100644 husarion_ugv_msg/srv/SetLEDImageAnimation.srv rename {husarion_ugv_msg => husarion_ugv_msgs}/CHANGELOG.rst (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/CMakeLists.txt (96%) rename {husarion_ugv_msg => husarion_ugv_msgs}/README.md (72%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/ChargingStatus.msg (100%) create mode 100644 husarion_ugv_msgs/msg/DriverState.msg rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/DriverStateNamed.msg (73%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/FaultFlag.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/IOState.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/LEDAnimation.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/LEDAnimationQueue.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/LEDImageAnimation.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/RobotDriverState.msg (71%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/RuntimeError.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/ScriptFlag.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/msg/SystemStatus.msg (100%) rename {husarion_ugv_msg => husarion_ugv_msgs}/package.xml (97%) rename {husarion_ugv_msg => husarion_ugv_msgs}/srv/SetLEDAnimation.srv (53%) rename {husarion_ugv_msg => husarion_ugv_msgs}/srv/SetLEDBrightness.srv (100%) create mode 100644 husarion_ugv_msgs/srv/SetLEDImageAnimation.srv diff --git a/ROS_API.md b/ROS_API.md index 7522843fc..c5eb4675c 100644 --- a/ROS_API.md +++ b/ROS_API.md @@ -68,7 +68,7 @@ Below is information about the physical robot API. For the simulation, topics an | 🤖 | 🖥️ | Topic | Description | | --- | --- | ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | ✅ | ✅ | `battery/battery_status` | Mean values of both batteries will be published if the robot has two batteries. Otherwise, the state of the single battery will be published.
[*sensor_msgs/BatteryState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/BatteryState.html) | -| ✅ | ❌ | `battery/charging_status` | Battery charging status value.
[*husarion_ugv_msg/ChargingStatus*](https://github.com/husarion/husarion_ugv_msg) | +| ✅ | ❌ | `battery/charging_status` | Battery charging status value.
[*husarion_ugv_msgs/ChargingStatus*](https://github.com/husarion/husarion_ugv_msgs) | | ✅ | ✅ | `cmd_vel` | Command velocity value.
[*geometry_msgs/Twist*](https://docs.ros2.org/latest/api/geometry_msgs/msg/Twist.html) | | ✅ | ✅ | `diagnostics` | Diagnostic data.
[*diagnostic_msgs/DiagnosticArray*](https://docs.ros2.org/latest/api/diagnostic_msgs/msg/DiagnosticArray.html) | | ✅ | ✅ | `dynamic_joint_states` | Information about the state of various movable joints in a robotic system.
[*control_msgs/DynamicJointState*](https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/DynamicJointState.msg) | @@ -77,8 +77,8 @@ Below is information about the physical robot API. For the simulation, topics an | ✅ | ❌ | `gps/time_reference` | The timestamp from the GPS device.
[*sensor_msgs/TimeReference*](https://docs.ros2.org/latest/api/sensor_msgs/msg/TimeReference.html) | | ✅ | ❌ | `gps/vel` | Velocity output from the GPS device.
[*geometry_msgs/TwistStamped*](https://docs.ros2.org/latest/api/geometry_msgs/msg/TwistStamped.html) | | ✅ | ✅ | `hardware/e_stop` | Current E-stop state.
[*std_msgs/Bool*](https://docs.ros2.org/latest/api/std_msgs/msg/Bool.html). | -| ✅ | ❌ | `hardware/io_state` | Current IO state.
[*husarion_ugv_msg/IOState*](https://github.com/husarion/husarion_ugv_msg) | -| ✅ | ✅ | `hardware/robot_driver_state` | Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
[*husarion_ugv_msg/RobotDriverState*](https://github.com/husarion/husarion_ugv_msg) | +| ✅ | ❌ | `hardware/io_state` | Current IO state.
[*husarion_ugv_msgs/IOState*](https://github.com/husarion/husarion_ugv_msgs) | +| ✅ | ✅ | `hardware/robot_driver_state` | Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
[*husarion_ugv_msgs/RobotDriverState*](https://github.com/husarion/husarion_ugv_msgs) | | ✅ | ✅ | `imu/data` | Filtered IMU data.
[*sensor_msgs/Imu*](https://docs.ros2.org/latest/api/sensor_msgs/msg/Imu.html) | | ✅ | ✅ | `joint_states` | Provides information about the state of various joints in a robotic system.
[*sensor_msgs/JointState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/JointState.html) | | ✅ | ✅ | `lights/channel_1_frame` | Frame to be displayed on robot Front Bumper Lights.
[*sensor_msgs/Image*](https://docs.ros2.org/latest/api/sensor_msgs/msg/Image.html) | @@ -87,7 +87,7 @@ Below is information about the physical robot API. For the simulation, topics an | ✅ | ✅ | `odometry/filtered` | Contains information about the filtered position and orientation. When `localization_mode` is `relative`, the position and orientation are relative to the starting point. When `localization_mode` is `enu`, the orientation is relative to the east-north-up (ENU) coordinates.
[*nav_msgs/Odometry*](https://docs.ros2.org/latest/api/nav_msgs/msg/Odometry.html) | | ✅ | ✅ | `odometry/wheels` | Robot odometry calculated from wheels.
[*nav_msgs/Odometry*](https://docs.ros2.org/latest/api/nav_msgs/msg/Odometry.html) | | ✅ | ✅ | `robot_description` | Contains information about robot description from URDF file.
[*std_msgs/String*](https://docs.ros2.org/latest/api/std_msgs/msg/String.html) | -| ✅ | ❌ | `system_status` | State of the system, including Built-in Computer's CPU temperature and load.
[*husarion_ugv_msg/SystemStatus*](https://github.com/husarion/husarion_ugv_msg) | +| ✅ | ❌ | `system_status` | State of the system, including Built-in Computer's CPU temperature and load.
[*husarion_ugv_msgs/SystemStatus*](https://github.com/husarion/husarion_ugv_msgs) | | ✅ | ✅ | `tf` | Transforms of robot system.
[*tf2_msgs/TFMessage*](https://docs.ros2.org/latest/api/tf2_msgs/msg/TFMessage.html) | | ✅ | ✅ | `tf_static` | Static transforms of robot system.
[*tf2_msgs/TFMessage*](https://docs.ros2.org/latest/api/tf2_msgs/msg/TFMessage.html) | @@ -121,8 +121,8 @@ Below is information about the physical robot API. For the simulation, topics an | ✅ | ✅ | `hardware/e_stop_trigger` | Triggers E-stop.
[std_srvs/srv/Trigger](https://docs.ros2.org/latest/api/std_srvs/srv/Trigger.html) | | ✅ | ❌ | `hardware/fan_enable` | Enables or disables fan.
[std_srvs/srv/SetBool](https://docs.ros2.org/latest/api/std_srvs/srv/SetBool.html) | | ✅ | ❌ | `hardware/motor_power_enable` | Enables or disables motor power.
[std_srvs/srv/SetBool](https://docs.ros2.org/latest/api/std_srvs/srv/SetBool.html) | -| ✅ | ✅ | `lights/set_animation` | Sets LED animation.
[husarion_ugv_msg/srv/SetLEDAnimation](https://github.com/husarion/husarion_ugv_msg) | +| ✅ | ✅ | `lights/set_animation` | Sets LED animation.
[husarion_ugv_msgs/srv/SetLEDAnimation](https://github.com/husarion/husarion_ugv_msgs) | | ✅ | ✅ | `localization/enable` | Enable EKF node.
[std_srvs/srv/Empty](https://docs.ros2.org/latest/api/std_srvs/srv/Empty.html) | -| ✅ | ❌ | `lights/set_brightness` | Sets global LED brightness, value ranges from **0.0** to **1.0**.
[husarion_ugv_msg/SetLEDBrightness](https://github.com/husarion/husarion_ugv_msg) | +| ✅ | ❌ | `lights/set_brightness` | Sets global LED brightness, value ranges from **0.0** to **1.0**.
[husarion_ugv_msgs/SetLEDBrightness](https://github.com/husarion/husarion_ugv_msgs) | | ✅ | ✅ | `localization/set_pose` | Set pose of EKF node.
[robot_localization/srv/SetPose](https://github.com/cra-ros-pkg/robot_localization/tree/ros2) | | ✅ | ✅ | `localization/toggle` | Toggle filter processing in the EKF node.
[robot_localization/srv/ToggleFilterProcessing](https://github.com/cra-ros-pkg/robot_localization/tree/ros2) | diff --git a/husarion_ugv_battery/CMakeLists.txt b/husarion_ugv_battery/CMakeLists.txt index 91a52e789..f6834a3ab 100644 --- a/husarion_ugv_battery/CMakeLists.txt +++ b/husarion_ugv_battery/CMakeLists.txt @@ -5,7 +5,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater husarion_ugv_msg +set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs) foreach(PACKAGE IN ITEMS ${PACKAGE_DEPENDENCIES}) @@ -45,7 +45,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_battery rclcpp sensor_msgs - husarion_ugv_msg) + husarion_ugv_msgs) ament_add_gtest(${PROJECT_NAME}_test_adc_battery test/battery/test_adc_battery.cpp src/battery/adc_battery.cpp) @@ -54,7 +54,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_adc_battery rclcpp sensor_msgs - husarion_ugv_msg) + husarion_ugv_msgs) ament_add_gtest( ${PROJECT_NAME}_test_roboteq_battery test/battery/test_roboteq_battery.cpp @@ -64,7 +64,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_battery - husarion_ugv_msg rclcpp sensor_msgs) + husarion_ugv_msgs rclcpp sensor_msgs) ament_add_gtest( ${PROJECT_NAME}_test_battery_publisher diff --git a/husarion_ugv_battery/README.md b/husarion_ugv_battery/README.md index cc67f082f..9c5f67007 100644 --- a/husarion_ugv_battery/README.md +++ b/husarion_ugv_battery/README.md @@ -19,13 +19,13 @@ Publishes battery state read from ADC unit. - `_battery/battery_1_status_raw` [*sensor_msgs/BatteryState*]: First battery raw state. - `_battery/battery_2_status_raw` [*sensor_msgs/BatteryState*]: Second battery raw state. Published if second battery detected. - `battery/battery_status` [*sensor_msgs/BatteryState*]: Mean values of both batteries if robot has two batteries. Otherwise, the state of the single battery will be published. -- `battery/charging_status` [*husarion_ugv_msg/ChargingStatus*]: Battery charging status. +- `battery/charging_status` [*husarion_ugv_msgs/ChargingStatus*]: Battery charging status. - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: Battery diagnostic messages. #### Subscribers -- `hardware/io_state` [*husarion_ugv_msg/IOState*]: Current state of IO. -- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data. +- `hardware/io_state` [*husarion_ugv_msgs/IOState*]: Current state of IO. +- `hardware/robot_driver_state` [*husarion_ugv_msgs/RobotDriverState*]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data. #### Parameters diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp index 8a914c547..396445dda 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp @@ -25,13 +25,13 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/charging_status.hpp" +#include "husarion_ugv_msgs/msg/charging_status.hpp" namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus; class Battery { diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp index 8423d4b83..bced7013a 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp @@ -21,8 +21,8 @@ #include "rclcpp/rclcpp.hpp" -#include "husarion_ugv_msg/msg/driver_state_named.hpp" -#include "husarion_ugv_msg/msg/robot_driver_state.hpp" +#include "husarion_ugv_msgs/msg/driver_state_named.hpp" +#include "husarion_ugv_msgs/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/battery/battery.hpp" #include "husarion_ugv_utils/moving_average.hpp" @@ -30,8 +30,8 @@ namespace husarion_ugv_battery { -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; -using DriverStateNamedMsg = husarion_ugv_msg::msg::DriverStateNamed; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; +using DriverStateNamedMsg = husarion_ugv_msgs::msg::DriverStateNamed; struct RoboteqBatteryParams { diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp index ea9069f83..10f17070c 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp @@ -21,7 +21,7 @@ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" -#include "husarion_ugv_msg/msg/robot_driver_state.hpp" +#include "husarion_ugv_msgs/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/adc_data_reader.hpp" #include "husarion_ugv_battery/battery/battery.hpp" @@ -30,7 +30,7 @@ namespace husarion_ugv_battery { -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; class BatteryDriverNode : public rclcpp::Node { diff --git a/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp index 51b166a49..9dd76f7cb 100644 --- a/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp @@ -22,15 +22,15 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/charging_status.hpp" -#include "husarion_ugv_msg/msg/io_state.hpp" +#include "husarion_ugv_msgs/msg/charging_status.hpp" +#include "husarion_ugv_msgs/msg/io_state.hpp" namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; -using IOStateMsg = husarion_ugv_msg::msg::IOState; +using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus; +using IOStateMsg = husarion_ugv_msgs::msg::IOState; class BatteryPublisher { diff --git a/husarion_ugv_battery/package.xml b/husarion_ugv_battery/package.xml index c75ea9aa5..d00515394 100644 --- a/husarion_ugv_battery/package.xml +++ b/husarion_ugv_battery/package.xml @@ -17,7 +17,7 @@ ament_cmake diagnostic_updater - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs diff --git a/husarion_ugv_battery/test/battery/test_adc_battery.cpp b/husarion_ugv_battery/test/battery/test_adc_battery.cpp index 53607796c..5decb41d8 100644 --- a/husarion_ugv_battery/test/battery/test_adc_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_adc_battery.cpp @@ -22,13 +22,13 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/charging_status.hpp" +#include "husarion_ugv_msgs/msg/charging_status.hpp" #include "husarion_ugv_battery/battery/adc_battery.hpp" #include "husarion_ugv_utils/test/test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus; class TestADCBattery : public testing::Test { diff --git a/husarion_ugv_battery/test/battery/test_battery.cpp b/husarion_ugv_battery/test/battery/test_battery.cpp index 5f5536bf5..ad9b3e037 100644 --- a/husarion_ugv_battery/test/battery/test_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_battery.cpp @@ -22,13 +22,13 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/charging_status.hpp" +#include "husarion_ugv_msgs/msg/charging_status.hpp" #include "husarion_ugv_battery/battery/battery.hpp" #include "husarion_ugv_utils/test/test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus; class BatteryWrapper : public husarion_ugv_battery::Battery { diff --git a/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp b/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp index 089e989d7..7fad2649a 100644 --- a/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp @@ -24,14 +24,14 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/driver_state_named.hpp" -#include "husarion_ugv_msg/msg/robot_driver_state.hpp" +#include "husarion_ugv_msgs/msg/driver_state_named.hpp" +#include "husarion_ugv_msgs/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/battery/roboteq_battery.hpp" #include "husarion_ugv_utils/test/test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; class RoboteqBatteryWrapper : public husarion_ugv_battery::RoboteqBattery { @@ -81,8 +81,8 @@ void TestRoboteqBattery::UpdateBattery(const float voltage, const float current) { if (!driver_state_) { driver_state_ = std::make_shared(); - driver_state_->driver_states.push_back(husarion_ugv_msg::msg::DriverStateNamed()); - driver_state_->driver_states.push_back(husarion_ugv_msg::msg::DriverStateNamed()); + driver_state_->driver_states.push_back(husarion_ugv_msgs::msg::DriverStateNamed()); + driver_state_->driver_states.push_back(husarion_ugv_msgs::msg::DriverStateNamed()); } auto stamp = rclcpp::Time(0, 0, RCL_ROS_TIME); diff --git a/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp index 249c3193f..a571411a3 100644 --- a/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp @@ -22,12 +22,12 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/io_state.hpp" +#include "husarion_ugv_msgs/msg/io_state.hpp" #include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using IOStateMsg = husarion_ugv_msg::msg::IOState; +using IOStateMsg = husarion_ugv_msgs::msg::IOState; class BatteryPublisherWrapper : public husarion_ugv_battery::BatteryPublisher { diff --git a/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp index 959febfc4..46cabbf91 100644 --- a/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp @@ -22,7 +22,7 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/charging_status.hpp" +#include "husarion_ugv_msgs/msg/charging_status.hpp" #include "husarion_ugv_battery/battery/adc_battery.hpp" #include "husarion_ugv_battery/battery/battery.hpp" @@ -30,7 +30,7 @@ #include "husarion_ugv_utils/test/ros_test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus; +using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus; class DualBatteryPublisherWrapper : public husarion_ugv_battery::DualBatteryPublisher { diff --git a/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp b/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp index 5e02ab8cd..8158c8b81 100644 --- a/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp +++ b/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp @@ -44,7 +44,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryValues) EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_STATUS_UNKNOWN, battery_state_->power_supply_status); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_HEALTH_UNKNOWN, battery_state_->power_supply_health); - husarion_ugv_msg::msg::DriverStateNamed motor_controller; + husarion_ugv_msgs::msg::DriverStateNamed motor_controller; motor_controller.state.voltage = 35.0f; motor_controller.state.current = 0.1f; @@ -84,7 +84,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryTimeout) EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_HEALTH_UNKNOWN, battery_state_->power_supply_health); // Publish some values - husarion_ugv_msg::msg::DriverStateNamed motor_controller; + husarion_ugv_msgs::msg::DriverStateNamed motor_controller; motor_controller.state.voltage = 35.0f; motor_controller.state.current = 0.1f; diff --git a/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp b/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp index 5e061fbda..2e496b88b 100644 --- a/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp +++ b/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp @@ -28,14 +28,14 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "husarion_ugv_msg/msg/io_state.hpp" -#include "husarion_ugv_msg/msg/robot_driver_state.hpp" +#include "husarion_ugv_msgs/msg/io_state.hpp" +#include "husarion_ugv_msgs/msg/robot_driver_state.hpp" #include "husarion_ugv_battery/battery_driver_node.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; -using IOStateMsg = husarion_ugv_msg::msg::IOState; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; +using IOStateMsg = husarion_ugv_msgs::msg::IOState; class TestBatteryNode : public testing::Test { diff --git a/husarion_ugv_diagnostics/CMakeLists.txt b/husarion_ugv_diagnostics/CMakeLists.txt index 35282f60b..a4d9d02e4 100644 --- a/husarion_ugv_diagnostics/CMakeLists.txt +++ b/husarion_ugv_diagnostics/CMakeLists.txt @@ -20,7 +20,7 @@ set(PACKAGE_DEPENDENCIES diagnostic_msgs diagnostic_updater generate_parameter_library - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils PkgConfig rclcpp diff --git a/husarion_ugv_diagnostics/README.md b/husarion_ugv_diagnostics/README.md index 78440b1bf..f21439ca9 100644 --- a/husarion_ugv_diagnostics/README.md +++ b/husarion_ugv_diagnostics/README.md @@ -19,7 +19,7 @@ Publishes the built-in computer system status , monitoring parameters as such as #### Publishes - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: System monitor diagnostic messages. -- `system_status` [*husarion_ugv_msg/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. +- `system_status` [*husarion_ugv_msgs/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. #### Parameters diff --git a/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp index 4941b9be7..73bf99184 100644 --- a/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp +++ b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp @@ -20,7 +20,7 @@ #include #include -#include "husarion_ugv_msg/msg/system_status.hpp" +#include "husarion_ugv_msgs/msg/system_status.hpp" #include "system_monitor_parameters.hpp" @@ -63,7 +63,7 @@ class SystemMonitorNode : public rclcpp::Node * @param status The SystemStatus object to be converted. * @return The converted SystemStatus message. */ - husarion_ugv_msg::msg::SystemStatus SystemStatusToMessage(const SystemStatus & status); + husarion_ugv_msgs::msg::SystemStatus SystemStatusToMessage(const SystemStatus & status); private: void TimerCallback(); @@ -73,7 +73,7 @@ class SystemMonitorNode : public rclcpp::Node diagnostic_updater::Updater diagnostic_updater_; rclcpp::TimerBase::SharedPtr timer_; - rclcpp::Publisher::SharedPtr system_status_publisher_; + rclcpp::Publisher::SharedPtr system_status_publisher_; system_monitor::Params params_; std::shared_ptr param_listener_; diff --git a/husarion_ugv_diagnostics/package.xml b/husarion_ugv_diagnostics/package.xml index 98beb7625..f3102cd3b 100644 --- a/husarion_ugv_diagnostics/package.xml +++ b/husarion_ugv_diagnostics/package.xml @@ -20,7 +20,7 @@ diagnostic_msgs diagnostic_updater generate_parameter_library - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp std_msgs diff --git a/husarion_ugv_diagnostics/src/system_monitor_node.cpp b/husarion_ugv_diagnostics/src/system_monitor_node.cpp index bdcf20e11..09be7e042 100644 --- a/husarion_ugv_diagnostics/src/system_monitor_node.cpp +++ b/husarion_ugv_diagnostics/src/system_monitor_node.cpp @@ -22,7 +22,7 @@ #include #include -#include "husarion_ugv_msg/msg/system_status.hpp" +#include "husarion_ugv_msgs/msg/system_status.hpp" #include "husarion_ugv_utils/common_utilities.hpp" #include "husarion_ugv_utils/ros_utils.hpp" @@ -44,7 +44,7 @@ SystemMonitorNode::SystemMonitorNode( std::make_shared(this->get_node_parameters_interface()); params_ = param_listener_->get_params(); - system_status_publisher_ = this->create_publisher( + system_status_publisher_ = this->create_publisher( "system_status", 10); const auto timer_interval_ms = static_cast(1000.0 / params_.publish_frequency); @@ -149,10 +149,10 @@ float SystemMonitorNode::GetDiskUsage() const return disk_usage; } -husarion_ugv_msg::msg::SystemStatus SystemMonitorNode::SystemStatusToMessage( +husarion_ugv_msgs::msg::SystemStatus SystemMonitorNode::SystemStatusToMessage( const SystemStatus & status) { - husarion_ugv_msg::msg::SystemStatus message; + husarion_ugv_msgs::msg::SystemStatus message; message.header.stamp = this->get_clock()->now(); message.cpu_percent = status.core_usages; diff --git a/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py b/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py index e5d5df434..4fe7da96b 100644 --- a/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py +++ b/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py @@ -24,7 +24,7 @@ from launch_ros.actions import Node from launch_testing_ros import WaitForTopics -from husarion_ugv_msg.msg import SystemStatus +from husarion_ugv_msgs.msg import SystemStatus @pytest.mark.launch_test diff --git a/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp b/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp index c48ca35c9..522e44088 100644 --- a/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp +++ b/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp @@ -62,7 +62,7 @@ class SystemMonitorNodeWrapper : public husarion_ugv_diagnostics::SystemMonitorN float GetDiskUsage() const { return husarion_ugv_diagnostics::SystemMonitorNode::GetDiskUsage(); } - husarion_ugv_msg::msg::SystemStatus SystemStatusToMessage( + husarion_ugv_msgs::msg::SystemStatus SystemStatusToMessage( const husarion_ugv_diagnostics::SystemStatus & status) { diff --git a/husarion_ugv_hardware_interfaces/CMakeLists.txt b/husarion_ugv_hardware_interfaces/CMakeLists.txt index 2036cda09..abeb42eff 100644 --- a/husarion_ugv_hardware_interfaces/CMakeLists.txt +++ b/husarion_ugv_hardware_interfaces/CMakeLists.txt @@ -23,7 +23,7 @@ set(PACKAGE_DEPENDENCIES geometry_msgs hardware_interface imu_filter_madgwick - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils phidgets_api PkgConfig @@ -100,7 +100,7 @@ if(BUILD_TESTING) test/phidget_imu_sensor/test_phidget_imu_sensor.cpp) ament_target_dependencies( ${PROJECT_NAME}_test_phidget_imu_sensor hardware_interface rclcpp - husarion_ugv_utils husarion_ugv_msg phidgets_api) + husarion_ugv_utils husarion_ugv_msgs phidgets_api) target_link_libraries(${PROJECT_NAME}_test_phidget_imu_sensor ${PROJECT_NAME} phidgets_spatial_parameters) @@ -118,7 +118,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_data_converters - husarion_ugv_msg husarion_ugv_utils) + husarion_ugv_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_data_converters PkgConfig::LIBLELY_COAPP) @@ -131,7 +131,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_canopen_manager rclcpp - husarion_ugv_msg husarion_ugv_utils) + husarion_ugv_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_canopen_manager PkgConfig::LIBLELY_COAPP) @@ -146,7 +146,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_driver rclcpp - husarion_ugv_msg husarion_ugv_utils) + husarion_ugv_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_driver PkgConfig::LIBLELY_COAPP) @@ -163,7 +163,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_robot_driver rclcpp - husarion_ugv_msg husarion_ugv_utils) + husarion_ugv_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_robot_driver PkgConfig::LIBLELY_COAPP) @@ -181,7 +181,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_lynx_robot_driver rclcpp - husarion_ugv_msg husarion_ugv_utils) + husarion_ugv_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_lynx_robot_driver PkgConfig::LIBLELY_COAPP) @@ -199,7 +199,7 @@ if(BUILD_TESTING) PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_panther_robot_driver rclcpp - husarion_ugv_msg husarion_ugv_utils) + husarion_ugv_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_panther_robot_driver PkgConfig::LIBLELY_COAPP) @@ -228,7 +228,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_system_ros_interface diagnostic_updater rclcpp - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils realtime_tools std_srvs) @@ -256,7 +256,7 @@ if(BUILD_TESTING) diagnostic_updater hardware_interface rclcpp - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils std_msgs std_srvs) @@ -289,7 +289,7 @@ if(BUILD_TESTING) diagnostic_updater hardware_interface rclcpp - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils std_msgs std_srvs) @@ -323,7 +323,7 @@ if(BUILD_TESTING) diagnostic_updater hardware_interface rclcpp - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils std_msgs std_srvs) diff --git a/husarion_ugv_hardware_interfaces/README.md b/husarion_ugv_hardware_interfaces/README.md index a34b865a3..da6e06ae6 100644 --- a/husarion_ugv_hardware_interfaces/README.md +++ b/husarion_ugv_hardware_interfaces/README.md @@ -14,8 +14,8 @@ Plugins for Panther and Lynx are based on an abstraction called UGVSystem. Most - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: System diagnostic messages. - `hardware/e_stop` [*std_msgs/Bool*]: Current E-stop state. -- `hardware/io_state` [*husarion_ugv_msg/IOState*]: Current IO state. -- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: Current motor controllers' state and error flags. +- `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 diff --git a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp index 81cdf7878..b5607a810 100644 --- a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp @@ -21,9 +21,9 @@ #include #include -#include "husarion_ugv_msg/msg/fault_flag.hpp" -#include "husarion_ugv_msg/msg/runtime_error.hpp" -#include "husarion_ugv_msg/msg/script_flag.hpp" +#include "husarion_ugv_msgs/msg/fault_flag.hpp" +#include "husarion_ugv_msgs/msg/runtime_error.hpp" +#include "husarion_ugv_msgs/msg/script_flag.hpp" #include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp" #include "husarion_ugv_hardware_interfaces/utils.hpp" @@ -124,7 +124,7 @@ class FaultFlag : public FlagError { public: FaultFlag(); - husarion_ugv_msg::msg::FaultFlag GetMessage() const; + husarion_ugv_msgs::msg::FaultFlag GetMessage() const; std::map GetErrorMap() const; }; @@ -132,7 +132,7 @@ class ScriptFlag : public FlagError { public: ScriptFlag(); - husarion_ugv_msg::msg::ScriptFlag GetMessage() const; + husarion_ugv_msgs::msg::ScriptFlag GetMessage() const; std::map GetErrorMap() const; }; @@ -140,7 +140,7 @@ class RuntimeError : public FlagError { public: RuntimeError(); - husarion_ugv_msg::msg::RuntimeError GetMessage() const; + husarion_ugv_msgs::msg::RuntimeError GetMessage() const; std::map GetErrorMap() const; }; diff --git a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp index 48a1abf8e..bf7ce90a4 100644 --- a/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_ros_interface.hpp @@ -30,9 +30,9 @@ #include #include -#include "husarion_ugv_msg/msg/driver_state_named.hpp" -#include "husarion_ugv_msg/msg/io_state.hpp" -#include "husarion_ugv_msg/msg/robot_driver_state.hpp" +#include "husarion_ugv_msgs/msg/driver_state_named.hpp" +#include "husarion_ugv_msgs/msg/io_state.hpp" +#include "husarion_ugv_msgs/msg/robot_driver_state.hpp" #include "husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_controller.hpp" #include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp" @@ -43,9 +43,9 @@ namespace husarion_ugv_hardware_interfaces { using BoolMsg = std_msgs::msg::Bool; -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; -using IOStateMsg = husarion_ugv_msg::msg::IOState; -using DriverStateNamedMsg = husarion_ugv_msg::msg::DriverStateNamed; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; +using IOStateMsg = husarion_ugv_msgs::msg::IOState; +using DriverStateNamedMsg = husarion_ugv_msgs::msg::DriverStateNamed; using SetBoolSrv = std_srvs::srv::SetBool; using TriggerSrv = std_srvs::srv::Trigger; diff --git a/husarion_ugv_hardware_interfaces/package.xml b/husarion_ugv_hardware_interfaces/package.xml index b45a4d6ff..06aefd770 100644 --- a/husarion_ugv_hardware_interfaces/package.xml +++ b/husarion_ugv_hardware_interfaces/package.xml @@ -31,7 +31,7 @@ generate_parameter_library geometry_msgs hardware_interface - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils imu_filter_madgwick phidgets_api diff --git a/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp b/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp index 6f3974c97..ead973285 100644 --- a/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp +++ b/husarion_ugv_hardware_interfaces/src/robot_system/robot_driver/roboteq_data_converters.cpp @@ -110,9 +110,9 @@ FaultFlag::FaultFlag() { } -husarion_ugv_msg::msg::FaultFlag FaultFlag::GetMessage() const +husarion_ugv_msgs::msg::FaultFlag FaultFlag::GetMessage() const { - husarion_ugv_msg::msg::FaultFlag fault_flags_msg; + husarion_ugv_msgs::msg::FaultFlag fault_flags_msg; fault_flags_msg.overheat = flags_.test(0); fault_flags_msg.overvoltage = flags_.test(1); @@ -137,9 +137,9 @@ std::map FaultFlag::GetErrorMap() const ScriptFlag::ScriptFlag() : FlagError({"loop_error", "encoder_disconnected", "amp_limiter"}) {} -husarion_ugv_msg::msg::ScriptFlag ScriptFlag::GetMessage() const +husarion_ugv_msgs::msg::ScriptFlag ScriptFlag::GetMessage() const { - husarion_ugv_msg::msg::ScriptFlag script_flags_msg; + husarion_ugv_msgs::msg::ScriptFlag script_flags_msg; script_flags_msg.loop_error = flags_.test(0); script_flags_msg.encoder_disconnected = flags_.test(1); @@ -178,9 +178,9 @@ RuntimeError::RuntimeError() { } -husarion_ugv_msg::msg::RuntimeError RuntimeError::GetMessage() const +husarion_ugv_msgs::msg::RuntimeError RuntimeError::GetMessage() const { - husarion_ugv_msg::msg::RuntimeError runtime_errors_msg; + husarion_ugv_msgs::msg::RuntimeError runtime_errors_msg; runtime_errors_msg.amps_limit_active = flags_.test(0); runtime_errors_msg.motor_stall = flags_.test(1); diff --git a/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp b/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp index 7f40f6c78..53cf5a886 100644 --- a/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp +++ b/husarion_ugv_hardware_interfaces/test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp @@ -24,7 +24,7 @@ #include "utils/test_constants.hpp" void TestFaultFlagMsg( - const husarion_ugv_msg::msg::FaultFlag & msg, const std::vector & expected_values) + const husarion_ugv_msgs::msg::FaultFlag & msg, const std::vector & expected_values) { if (expected_values.size() != 8) { throw std::runtime_error("Wrong size of expected_values in TestFaultFlagMsg"); @@ -41,7 +41,7 @@ void TestFaultFlagMsg( } void TestScriptFlagMsg( - const husarion_ugv_msg::msg::ScriptFlag & msg, const std::vector & expected_values) + const husarion_ugv_msgs::msg::ScriptFlag & msg, const std::vector & expected_values) { if (expected_values.size() != 3) { throw std::runtime_error("Wrong size of expected_values in TestScriptFlagMsg"); @@ -53,7 +53,7 @@ void TestScriptFlagMsg( } void TestRuntimeErrorMsg( - const husarion_ugv_msg::msg::RuntimeError & msg, const std::vector & expected_values) + const husarion_ugv_msgs::msg::RuntimeError & msg, const std::vector & expected_values) { if (expected_values.size() != 7) { throw std::runtime_error("Wrong size of expected_values in TestFaultFlagMsg"); diff --git a/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp b/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp index 271215c38..f51d502c0 100644 --- a/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp +++ b/husarion_ugv_hardware_interfaces/test/unit/robot_system/test_system_ros_interface.cpp @@ -26,7 +26,7 @@ #include "utils/test_constants.hpp" -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; class SystemROSInterfaceWrapper : public husarion_ugv_hardware_interfaces::SystemROSInterface { diff --git a/husarion_ugv_lights/CMakeLists.txt b/husarion_ugv_lights/CMakeLists.txt index c8b06b3c9..80b7985c1 100644 --- a/husarion_ugv_lights/CMakeLists.txt +++ b/husarion_ugv_lights/CMakeLists.txt @@ -9,7 +9,7 @@ set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater image_transport - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils pluginlib rclcpp @@ -37,7 +37,7 @@ ament_target_dependencies( lights_driver_node_component diagnostic_updater image_transport - husarion_ugv_msg + husarion_ugv_msgs rclcpp rclcpp_components sensor_msgs @@ -50,7 +50,7 @@ add_library( src/led_components/led_animations_queue.cpp) ament_target_dependencies( lights_controller_node_component - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils pluginlib rclcpp diff --git a/husarion_ugv_lights/CONFIGURATION.md b/husarion_ugv_lights/CONFIGURATION.md index 5e3f31d4c..b471198b1 100644 --- a/husarion_ugv_lights/CONFIGURATION.md +++ b/husarion_ugv_lights/CONFIGURATION.md @@ -158,7 +158,7 @@ ros2 launch husarion_ugv_bringup bringup.launch user_animations_file:=/my_awesom Test new animations: ```bash -ros2 service call /lights/set_animation husarion_ugv_msg/srv/SetLEDAnimation "{animation: {id: 0, param: ''}, repeating: true}" +ros2 service call /lights/set_animation husarion_ugv_msgs/srv/SetLEDAnimation "{animation: {id: 0, param: ''}, repeating: true}" ``` ## Defining a Custom Animation Type diff --git a/husarion_ugv_lights/README.md b/husarion_ugv_lights/README.md index 124f10550..12bc7696c 100644 --- a/husarion_ugv_lights/README.md +++ b/husarion_ugv_lights/README.md @@ -26,7 +26,7 @@ This node is of type rclcpp_components is responsible for processing animations #### Service Servers -- `lights/set_animation` [*husarion_ugv_msg/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. +- `lights/set_animation` [*husarion_ugv_msgs/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. #### Parameters @@ -49,7 +49,7 @@ This node is of type rclcpp_components is responsible for displaying frames on t #### Service Servers -- `lights/set_brightness` [*husarion_ugv_msg/SetLEDBrightness*]: Allows setting global LED brightness, value ranges from **0.0** to **1.0**. +- `lights/set_brightness` [*husarion_ugv_msgs/SetLEDBrightness*]: Allows setting global LED brightness, value ranges from **0.0** to **1.0**. #### Service Clients diff --git a/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp b/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp index 2af12c820..79715bac4 100644 --- a/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp +++ b/husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp @@ -25,7 +25,7 @@ #include "sensor_msgs/msg/image.hpp" -#include "husarion_ugv_msg/srv/set_led_animation.hpp" +#include "husarion_ugv_msgs/srv/set_led_animation.hpp" #include "husarion_ugv_lights/animation/animation.hpp" #include "husarion_ugv_lights/led_components/led_animations_queue.hpp" @@ -36,7 +36,7 @@ namespace husarion_ugv_lights { using ImageMsg = sensor_msgs::msg::Image; -using SetLEDAnimationSrv = husarion_ugv_msg::srv::SetLEDAnimation; +using SetLEDAnimationSrv = husarion_ugv_msgs::srv::SetLEDAnimation; class LightsControllerNode : public rclcpp::Node { diff --git a/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp b/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp index 70107f621..4464e2a6f 100644 --- a/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp +++ b/husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp @@ -24,7 +24,7 @@ #include "sensor_msgs/msg/image.hpp" #include "std_srvs/srv/set_bool.hpp" -#include "husarion_ugv_msg/srv/set_led_brightness.hpp" +#include "husarion_ugv_msgs/srv/set_led_brightness.hpp" #include "husarion_ugv_lights/apa102.hpp" @@ -33,7 +33,7 @@ namespace husarion_ugv_lights using ImageMsg = sensor_msgs::msg::Image; using SetBoolSrv = std_srvs::srv::SetBool; -using SetLEDBrightnessSrv = husarion_ugv_msg::srv::SetLEDBrightness; +using SetLEDBrightnessSrv = husarion_ugv_msgs::srv::SetLEDBrightness; /** * @brief Class for controlling APA102 LEDs based on a ROS Image topic. diff --git a/husarion_ugv_lights/package.xml b/husarion_ugv_lights/package.xml index 99c671046..59be60e34 100644 --- a/husarion_ugv_lights/package.xml +++ b/husarion_ugv_lights/package.xml @@ -17,7 +17,7 @@ ament_cmake diagnostic_updater - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils image_transport libpng-dev diff --git a/husarion_ugv_lights/src/lights_controller_node.cpp b/husarion_ugv_lights/src/lights_controller_node.cpp index 1092f0ba0..7350a6e45 100644 --- a/husarion_ugv_lights/src/lights_controller_node.cpp +++ b/husarion_ugv_lights/src/lights_controller_node.cpp @@ -29,7 +29,7 @@ #include "sensor_msgs/msg/image.hpp" -#include "husarion_ugv_msg/srv/set_led_animation.hpp" +#include "husarion_ugv_msgs/srv/set_led_animation.hpp" #include "husarion_ugv_lights/led_components/led_animations_queue.hpp" #include "husarion_ugv_lights/led_components/led_panel.hpp" diff --git a/husarion_ugv_lights/src/lights_driver_node.cpp b/husarion_ugv_lights/src/lights_driver_node.cpp index 880811a5e..7d730328e 100644 --- a/husarion_ugv_lights/src/lights_driver_node.cpp +++ b/husarion_ugv_lights/src/lights_driver_node.cpp @@ -29,7 +29,7 @@ #include "sensor_msgs/msg/image.hpp" #include "std_srvs/srv/set_bool.hpp" -#include "husarion_ugv_msg/srv/set_led_brightness.hpp" +#include "husarion_ugv_msgs/srv/set_led_brightness.hpp" #include "husarion_ugv_lights/apa102.hpp" diff --git a/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py b/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py index 4aaa17251..2c107baa1 100644 --- a/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py +++ b/husarion_ugv_lights/test/integration/husarion_ugv_lights.test.py @@ -31,8 +31,8 @@ from sensor_msgs.msg import Image from std_srvs.srv import SetBool -from husarion_ugv_msg.msg import LEDAnimation -from husarion_ugv_msg.srv import SetLEDAnimation +from husarion_ugv_msgs.msg import LEDAnimation +from husarion_ugv_msgs.srv import SetLEDAnimation def generate_test_description(): diff --git a/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp b/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp index 5a941e51a..770721a0d 100644 --- a/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp +++ b/husarion_ugv_lights/test/unit/test_lights_driver_node.cpp @@ -23,7 +23,7 @@ #include #include -#include "husarion_ugv_msg/srv/set_led_brightness.hpp" +#include "husarion_ugv_msgs/srv/set_led_brightness.hpp" #include "husarion_ugv_lights/apa102.hpp" #include "husarion_ugv_lights/lights_driver_node.hpp" @@ -31,7 +31,7 @@ using ImageMsg = sensor_msgs::msg::Image; using SetBoolSrv = std_srvs::srv::SetBool; -using SetLEDBrightnessSrv = husarion_ugv_msg::srv::SetLEDBrightness; +using SetLEDBrightnessSrv = husarion_ugv_msgs::srv::SetLEDBrightness; class MockAPA102 : public husarion_ugv_lights::APA102Interface { diff --git a/husarion_ugv_manager/CMakeLists.txt b/husarion_ugv_manager/CMakeLists.txt index 04783438d..60cb7bf57 100644 --- a/husarion_ugv_manager/CMakeLists.txt +++ b/husarion_ugv_manager/CMakeLists.txt @@ -11,7 +11,7 @@ set(PACKAGE_DEPENDENCIES behaviortree_cpp behaviortree_ros2 libssh - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp rclcpp_action @@ -66,7 +66,7 @@ add_executable( ament_target_dependencies( safety_manager_node behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs @@ -79,7 +79,7 @@ add_executable( ament_target_dependencies( lights_manager_node behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs @@ -192,7 +192,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_lights_manager_node behaviortree_cpp behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs @@ -210,7 +210,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_lights_behavior_tree behaviortree_cpp behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs @@ -227,7 +227,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_safety_manager_node behaviortree_cpp behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs @@ -245,7 +245,7 @@ if(BUILD_TESTING) ${PROJECT_NAME}_test_safety_behavior_tree behaviortree_cpp behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils rclcpp sensor_msgs diff --git a/husarion_ugv_manager/CONFIGURATION.md b/husarion_ugv_manager/CONFIGURATION.md index cfe40bd8d..e28328914 100644 --- a/husarion_ugv_manager/CONFIGURATION.md +++ b/husarion_ugv_manager/CONFIGURATION.md @@ -67,7 +67,7 @@ For a BehaviorTree project to work correctly, it must contain a tree with correc - `CallSetBoolService` - allows calling the standard **std_srvs/SetBool** ROS service. Provided ports are: - `data` [*input*, *bool*, default: **None**]: service data - **true** or **false** value. - `service_name` [*input*, *string*, default: **None**]: ROS service name. -- `CallSetLedAnimationService` - allows calling custom type **husarion_ugv_msg/SetLEDAnimation** ROS service. The provided ports are: +- `CallSetLedAnimationService` - allows calling custom type **husarion_ugv_msgs/SetLEDAnimation** ROS service. The provided ports are: - `id` [*input*, *unsigned*, default: **None**]: animation ID. - `param` [*input*, *string*, default: **None**]: optional parameter passed to animation. - `repeating` [*input*, *bool*, default: **false**]: indicates if the animation should repeat. @@ -118,16 +118,16 @@ Default constant blackboard entries: - `CRITICAL_BATTERY_THRESHOLD_PERCENT` [*float*, default: **0.1**]: refers to `critical_battery_threshold_percent` ROS parameter. - `LOW_BATTERY_ANIM_PERIOD` [*float*, default: **30.0**]: refers to `low_battery_anim_period` ROS parameter. - `LOW_BATTERY_THRESHOLD_PERCENT` [*float*, default: **0.4**]: refers to `low_battery_threshold_percent` ROS parameter. -- `E_STOP_ANIM_ID` [*unsigned*, value: **0**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::E_STOP`. -- `READY_ANIM_ID` [*unsigned*, value: **1**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::READY`. -- `ERROR_ANIM_ID` [*unsigned*, value: **2**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::ERROR`. -- `MANUAL_ACTION_ANIM_ID` [*unsigned*, value: **3**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::MANUAL_ACTION`. -- `AUTONOMOUS_ACTION_ANIM_ID` [*unsigned*, value: **4**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::AUTONOMOUS_ACTION`. -- `GOAL_ACHIEVED_ANIM_ID` [*unsigned*, value: **5**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::GOAL_ACHIEVED`. -- `LOW_BATTERY_ANIM_ID` [*unsigned*, value: **6**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::LOW_BATTERY`. -- `CRITICAL_BATTERY_ANIM_ID` [*unsigned*, value: **7**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::CRITICAL_BATTERY`. -- `BATTERY_STATE_ANIM_ID` [*unsigned*, value: **8**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::BATTERY_STATE`. -- `CHARGING_BATTERY_ANIM_ID` [*unsigned*, value: **9**]: animation ID constant obtained from `husarion_ugv_msg::LEDAnimation::CHARGING_BATTERY`. +- `E_STOP_ANIM_ID` [*unsigned*, value: **0**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::E_STOP`. +- `READY_ANIM_ID` [*unsigned*, value: **1**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::READY`. +- `ERROR_ANIM_ID` [*unsigned*, value: **2**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::ERROR`. +- `MANUAL_ACTION_ANIM_ID` [*unsigned*, value: **3**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::MANUAL_ACTION`. +- `AUTONOMOUS_ACTION_ANIM_ID` [*unsigned*, value: **4**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::AUTONOMOUS_ACTION`. +- `GOAL_ACHIEVED_ANIM_ID` [*unsigned*, value: **5**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::GOAL_ACHIEVED`. +- `LOW_BATTERY_ANIM_ID` [*unsigned*, value: **6**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::LOW_BATTERY`. +- `CRITICAL_BATTERY_ANIM_ID` [*unsigned*, value: **7**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::CRITICAL_BATTERY`. +- `BATTERY_STATE_ANIM_ID` [*unsigned*, value: **8**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::BATTERY_STATE`. +- `CHARGING_BATTERY_ANIM_ID` [*unsigned*, value: **9**]: animation ID constant obtained from `husarion_ugv_msgs::LEDAnimation::CHARGING_BATTERY`. - `POWER_SUPPLY_STATUS_UNKNOWN` [*unsigned*, value: **0**]: power supply status constant obtained from `sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN`. - `POWER_SUPPLY_STATUS_CHARGING` [*unsigned*, value: **1**]: power supply status constant obtained from `sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_CHARGING`. - `POWER_SUPPLY_STATUS_DISCHARGING` [*unsigned*, value: **2**]: power supply status constant obtained from `sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING`. diff --git a/husarion_ugv_manager/README.md b/husarion_ugv_manager/README.md index b58cc32e3..8c03979db 100644 --- a/husarion_ugv_manager/README.md +++ b/husarion_ugv_manager/README.md @@ -32,7 +32,7 @@ Node responsible for managing Bumper Lights animation scheduling. #### Service Clients (for Default Trees) -- `~/lights/set_animation` [*husarion_ugv_msg/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. +- `~/lights/set_animation` [*husarion_ugv_msgs/SetLEDAnimation*]: Allows setting animation on Bumper Lights based on animation ID. #### Parameters @@ -57,9 +57,9 @@ Node responsible for managing safety features, and software shutdown of componen - `battery/battery_status` [*sensor_msgs/BatteryState*]: State of the internal Battery. - `hardware/e_stop` [*std_msgs/Bool*]: State of emergency stop. -- `hardware/io_state` [*husarion_ugv_msg/IOState*]: State of IO pins. -- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: State of motor controllers. -- `system_status` [*husarion_ugv_msg/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. +- `hardware/io_state` [*husarion_ugv_msgs/IOState*]: State of IO pins. +- `hardware/robot_driver_state` [*husarion_ugv_msgs/RobotDriverState*]: State of motor controllers. +- `system_status` [*husarion_ugv_msgs/SystemStatus*]: Built-in computer system status, includes the most important computation-related parameters. #### Service Clients (for Default Trees) diff --git a/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp b/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp index c2d345933..71ed9aed0 100644 --- a/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp +++ b/husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp @@ -24,7 +24,7 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "husarion_ugv_msg/msg/led_animation.hpp" +#include "husarion_ugv_msgs/msg/led_animation.hpp" #include "husarion_ugv_utils/moving_average.hpp" @@ -35,7 +35,7 @@ namespace husarion_ugv_manager using BatteryStateMsg = sensor_msgs::msg::BatteryState; using BoolMsg = std_msgs::msg::Bool; -using LEDAnimationMsg = husarion_ugv_msg::msg::LEDAnimation; +using LEDAnimationMsg = husarion_ugv_msgs::msg::LEDAnimation; /** * @brief This class is responsible for creating a BehaviorTree responsible for lights management, diff --git a/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp b/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp index 9ce9ccea8..5bf4d25cf 100644 --- a/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp +++ b/husarion_ugv_manager/include/husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp @@ -20,17 +20,18 @@ #include "behaviortree_ros2/bt_service_node.hpp" #include "rclcpp/rclcpp.hpp" -#include "husarion_ugv_msg/srv/set_led_animation.hpp" +#include "husarion_ugv_msgs/srv/set_led_animation.hpp" namespace husarion_ugv_manager { -class CallSetLedAnimationService : public BT::RosServiceNode +class CallSetLedAnimationService +: public BT::RosServiceNode { public: CallSetLedAnimationService( const std::string & name, const BT::NodeConfig & conf, const BT::RosNodeParams & params) - : BT::RosServiceNode(name, conf, params) + : BT::RosServiceNode(name, conf, params) { } diff --git a/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp b/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp index dcd28a6db..ca1ccc15e 100644 --- a/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp +++ b/husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp @@ -25,9 +25,9 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "husarion_ugv_msg/msg/io_state.hpp" -#include "husarion_ugv_msg/msg/robot_driver_state.hpp" -#include "husarion_ugv_msg/msg/system_status.hpp" +#include "husarion_ugv_msgs/msg/io_state.hpp" +#include "husarion_ugv_msgs/msg/robot_driver_state.hpp" +#include "husarion_ugv_msgs/msg/system_status.hpp" #include "husarion_ugv_utils/moving_average.hpp" @@ -38,9 +38,9 @@ namespace husarion_ugv_manager using BatteryStateMsg = sensor_msgs::msg::BatteryState; using BoolMsg = std_msgs::msg::Bool; -using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState; -using IOStateMsg = husarion_ugv_msg::msg::IOState; -using SystemStatusMsg = husarion_ugv_msg::msg::SystemStatus; +using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState; +using IOStateMsg = husarion_ugv_msgs::msg::IOState; +using SystemStatusMsg = husarion_ugv_msgs::msg::SystemStatus; /** * @brief This class is responsible for creating a BehaviorTrees responsible for safety and shutdown diff --git a/husarion_ugv_manager/package.xml b/husarion_ugv_manager/package.xml index 5c110f73c..2c65f67fc 100644 --- a/husarion_ugv_manager/package.xml +++ b/husarion_ugv_manager/package.xml @@ -19,7 +19,7 @@ behaviortree_cpp behaviortree_ros2 - husarion_ugv_msg + husarion_ugv_msgs husarion_ugv_utils iputils-ping libboost-dev diff --git a/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp b/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp index a6717981c..2c3969c8c 100644 --- a/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp +++ b/husarion_ugv_manager/test/plugins/action/test_call_set_led_animation_service_node.cpp @@ -28,14 +28,14 @@ class TestCallSetLedAnimationService { public: void ServiceCallback( - const husarion_ugv_msg::srv::SetLEDAnimation::Request::SharedPtr request, - husarion_ugv_msg::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, + const husarion_ugv_msgs::srv::SetLEDAnimation::Request::SharedPtr request, + husarion_ugv_msgs::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, const std::size_t id, const bool repeating); }; void TestCallSetLedAnimationService::ServiceCallback( - const husarion_ugv_msg::srv::SetLEDAnimation::Request::SharedPtr request, - husarion_ugv_msg::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, + const husarion_ugv_msgs::srv::SetLEDAnimation::Request::SharedPtr request, + husarion_ugv_msgs::srv::SetLEDAnimation::Response::SharedPtr response, const bool success, const std::size_t id, const bool repeating) { response->message = success ? "Successfully callback pass!" : "Failed callback pass!"; @@ -98,7 +98,7 @@ TEST_F(TestCallSetLedAnimationService, GoodSetLedAnimationCallServiceSuccessWith CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using husarion_ugv_msg::srv::SetLEDAnimation; + using husarion_ugv_msgs::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( @@ -121,7 +121,7 @@ TEST_F(TestCallSetLedAnimationService, GoodSetLedAnimationCallServiceSuccessWith CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using husarion_ugv_msg::srv::SetLEDAnimation; + using husarion_ugv_msgs::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( @@ -144,7 +144,7 @@ TEST_F(TestCallSetLedAnimationService, GoodSetLedAnimationCallServiceSuccessWith CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using husarion_ugv_msg::srv::SetLEDAnimation; + using husarion_ugv_msgs::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( @@ -167,7 +167,7 @@ TEST_F(TestCallSetLedAnimationService, WrongSetLedAnimationCallServiceFailure) CreateTree("CallSetLedAnimationService", service); auto & tree = GetTree(); - using husarion_ugv_msg::srv::SetLEDAnimation; + using husarion_ugv_msgs::srv::SetLEDAnimation; CreateService( "set_led_animation", [&]( diff --git a/husarion_ugv_manager/test/test_lights_behavior_tree.cpp b/husarion_ugv_manager/test/test_lights_behavior_tree.cpp index de0d1c4d6..c5b496434 100644 --- a/husarion_ugv_manager/test/test_lights_behavior_tree.cpp +++ b/husarion_ugv_manager/test/test_lights_behavior_tree.cpp @@ -28,16 +28,16 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "std_msgs/msg/bool.hpp" -#include "husarion_ugv_msg/msg/led_animation.hpp" -#include "husarion_ugv_msg/srv/set_led_animation.hpp" +#include "husarion_ugv_msgs/msg/led_animation.hpp" +#include "husarion_ugv_msgs/srv/set_led_animation.hpp" #include #include using BoolMsg = std_msgs::msg::Bool; using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using SetLEDAnimationSrv = husarion_ugv_msg::srv::SetLEDAnimation; -using LEDAnimationMsg = husarion_ugv_msg::msg::LEDAnimation; +using SetLEDAnimationSrv = husarion_ugv_msgs::srv::SetLEDAnimation; +using LEDAnimationMsg = husarion_ugv_msgs::msg::LEDAnimation; class LightsManagerNodeWrapper : public husarion_ugv_manager::LightsManagerNode { diff --git a/husarion_ugv_manager/test/test_safety_behavior_tree.cpp b/husarion_ugv_manager/test/test_safety_behavior_tree.cpp index 9ddb01668..bfae5ac1d 100644 --- a/husarion_ugv_manager/test/test_safety_behavior_tree.cpp +++ b/husarion_ugv_manager/test/test_safety_behavior_tree.cpp @@ -30,16 +30,16 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" -#include "husarion_ugv_msg/msg/io_state.hpp" -#include "husarion_ugv_msg/msg/system_status.hpp" +#include "husarion_ugv_msgs/msg/io_state.hpp" +#include "husarion_ugv_msgs/msg/system_status.hpp" #include #include using BoolMsg = std_msgs::msg::Bool; using BatteryStateMsg = sensor_msgs::msg::BatteryState; -using IOStateMsg = husarion_ugv_msg::msg::IOState; -using SystemStatusMsg = husarion_ugv_msg::msg::SystemStatus; +using IOStateMsg = husarion_ugv_msgs::msg::IOState; +using SystemStatusMsg = husarion_ugv_msgs::msg::SystemStatus; using SetBoolSrv = std_srvs::srv::SetBool; using TriggerSrv = std_srvs::srv::Trigger; diff --git a/husarion_ugv_manager/test/test_safety_manager_node.cpp b/husarion_ugv_manager/test/test_safety_manager_node.cpp index 62c144df4..54033bff8 100644 --- a/husarion_ugv_manager/test/test_safety_manager_node.cpp +++ b/husarion_ugv_manager/test/test_safety_manager_node.cpp @@ -194,10 +194,10 @@ TEST_F(TestSafetyManagerNode, DriverStateCBBlackboardUpdate) { const float expected_temp = 21.0; - husarion_ugv_msg::msg::DriverStateNamed driver_state; + husarion_ugv_msgs::msg::DriverStateNamed driver_state; driver_state.state.temperature = expected_temp; - auto driver_state_msg = husarion_ugv_msg::msg::RobotDriverState(); + auto driver_state_msg = husarion_ugv_msgs::msg::RobotDriverState(); driver_state_msg.driver_states.push_back(driver_state); husarion_ugv_utils::test_utils::PublishAndSpin( @@ -212,7 +212,7 @@ TEST_F(TestSafetyManagerNode, IOStateCBBlackboardUpdate) const bool expected_aux_state = true; const bool expected_fan_state = true; - auto io_state_msg = husarion_ugv_msg::msg::IOState(); + auto io_state_msg = husarion_ugv_msgs::msg::IOState(); io_state_msg.aux_power = expected_aux_state; io_state_msg.fan = expected_fan_state; @@ -228,7 +228,7 @@ TEST_F(TestSafetyManagerNode, SystemStatusCBBlackboardUpdate) { const float expected_temp = 21.0; - auto system_status_msg = husarion_ugv_msg::msg::SystemStatus(); + auto system_status_msg = husarion_ugv_msgs::msg::SystemStatus(); system_status_msg.cpu_temp = expected_temp; husarion_ugv_utils::test_utils::PublishAndSpin( diff --git a/husarion_ugv_manager/test/utils/plugin_test_utils.hpp b/husarion_ugv_manager/test/utils/plugin_test_utils.hpp index d323b9a01..9b95e0a50 100644 --- a/husarion_ugv_manager/test/utils/plugin_test_utils.hpp +++ b/husarion_ugv_manager/test/utils/plugin_test_utils.hpp @@ -30,7 +30,7 @@ #include "std_srvs/srv/set_bool.hpp" #include "std_srvs/srv/trigger.hpp" -#include "husarion_ugv_msg/srv/set_led_animation.hpp" +#include "husarion_ugv_msgs/srv/set_led_animation.hpp" #include "husarion_ugv_manager/plugins/action/call_set_bool_service_node.hpp" #include "husarion_ugv_manager/plugins/action/call_set_led_animation_service_node.hpp" diff --git a/husarion_ugv_msg/msg/DriverState.msg b/husarion_ugv_msg/msg/DriverState.msg deleted file mode 100644 index 535a33cad..000000000 --- a/husarion_ugv_msg/msg/DriverState.msg +++ /dev/null @@ -1,14 +0,0 @@ -float32 voltage -float32 current -float32 temperature -float32 heatsink_temperature - -husarion_ugv_msg/FaultFlag fault_flag -husarion_ugv_msg/ScriptFlag script_flag -husarion_ugv_msg/RuntimeError channel_1_motor_runtime_error -husarion_ugv_msg/RuntimeError channel_2_motor_runtime_error - -bool motor_states_data_timed_out -bool driver_state_data_timed_out -bool can_error -bool heartbeat_timeout diff --git a/husarion_ugv_msg/srv/SetLEDImageAnimation.srv b/husarion_ugv_msg/srv/SetLEDImageAnimation.srv deleted file mode 100644 index 98474a614..000000000 --- a/husarion_ugv_msg/srv/SetLEDImageAnimation.srv +++ /dev/null @@ -1,7 +0,0 @@ -husarion_ugv_msg/LEDImageAnimation front -husarion_ugv_msg/LEDImageAnimation rear -bool interrupting -bool repeating ---- -bool success -string message diff --git a/husarion_ugv_msg/CHANGELOG.rst b/husarion_ugv_msgs/CHANGELOG.rst similarity index 100% rename from husarion_ugv_msg/CHANGELOG.rst rename to husarion_ugv_msgs/CHANGELOG.rst diff --git a/husarion_ugv_msg/CMakeLists.txt b/husarion_ugv_msgs/CMakeLists.txt similarity index 96% rename from husarion_ugv_msg/CMakeLists.txt rename to husarion_ugv_msgs/CMakeLists.txt index ab71cbdeb..a6261d0a2 100644 --- a/husarion_ugv_msg/CMakeLists.txt +++ b/husarion_ugv_msgs/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(husarion_ugv_msg) +project(husarion_ugv_msgs) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) diff --git a/husarion_ugv_msg/README.md b/husarion_ugv_msgs/README.md similarity index 72% rename from husarion_ugv_msg/README.md rename to husarion_ugv_msgs/README.md index a0ac941e1..5c72d2a5d 100644 --- a/husarion_ugv_msg/README.md +++ b/husarion_ugv_msgs/README.md @@ -1,3 +1,3 @@ -# husarion_ugv_msg +# husarion_ugv_msgs Custom ROS messages and services for Panther robot. diff --git a/husarion_ugv_msg/msg/ChargingStatus.msg b/husarion_ugv_msgs/msg/ChargingStatus.msg similarity index 100% rename from husarion_ugv_msg/msg/ChargingStatus.msg rename to husarion_ugv_msgs/msg/ChargingStatus.msg diff --git a/husarion_ugv_msgs/msg/DriverState.msg b/husarion_ugv_msgs/msg/DriverState.msg new file mode 100644 index 000000000..178e26391 --- /dev/null +++ b/husarion_ugv_msgs/msg/DriverState.msg @@ -0,0 +1,14 @@ +float32 voltage +float32 current +float32 temperature +float32 heatsink_temperature + +husarion_ugv_interfaces/FaultFlag fault_flag +husarion_ugv_interfaceserfaces/ScriptFlag script_flag +husarion_ugv_interfaceserfaces/RuntimeError channel_1_motor_runtime_error +husarion_ugv_interfaceserfaces/RuntimeError channel_2_motor_runtime_error + +bool motor_states_data_timed_out +bool driver_state_data_timed_out +bool can_error +bool heartbeat_timeout diff --git a/husarion_ugv_msg/msg/DriverStateNamed.msg b/husarion_ugv_msgs/msg/DriverStateNamed.msg similarity index 73% rename from husarion_ugv_msg/msg/DriverStateNamed.msg rename to husarion_ugv_msgs/msg/DriverStateNamed.msg index 6a3528b96..be91b417a 100644 --- a/husarion_ugv_msg/msg/DriverStateNamed.msg +++ b/husarion_ugv_msgs/msg/DriverStateNamed.msg @@ -3,4 +3,4 @@ string NAME_FRONT = "front" string NAME_REAR = "rear" string name -husarion_ugv_msg/DriverState state +husarion_ugv_msgs/DriverState state diff --git a/husarion_ugv_msg/msg/FaultFlag.msg b/husarion_ugv_msgs/msg/FaultFlag.msg similarity index 100% rename from husarion_ugv_msg/msg/FaultFlag.msg rename to husarion_ugv_msgs/msg/FaultFlag.msg diff --git a/husarion_ugv_msg/msg/IOState.msg b/husarion_ugv_msgs/msg/IOState.msg similarity index 100% rename from husarion_ugv_msg/msg/IOState.msg rename to husarion_ugv_msgs/msg/IOState.msg diff --git a/husarion_ugv_msg/msg/LEDAnimation.msg b/husarion_ugv_msgs/msg/LEDAnimation.msg similarity index 100% rename from husarion_ugv_msg/msg/LEDAnimation.msg rename to husarion_ugv_msgs/msg/LEDAnimation.msg diff --git a/husarion_ugv_msg/msg/LEDAnimationQueue.msg b/husarion_ugv_msgs/msg/LEDAnimationQueue.msg similarity index 100% rename from husarion_ugv_msg/msg/LEDAnimationQueue.msg rename to husarion_ugv_msgs/msg/LEDAnimationQueue.msg diff --git a/husarion_ugv_msg/msg/LEDImageAnimation.msg b/husarion_ugv_msgs/msg/LEDImageAnimation.msg similarity index 100% rename from husarion_ugv_msg/msg/LEDImageAnimation.msg rename to husarion_ugv_msgs/msg/LEDImageAnimation.msg diff --git a/husarion_ugv_msg/msg/RobotDriverState.msg b/husarion_ugv_msgs/msg/RobotDriverState.msg similarity index 71% rename from husarion_ugv_msg/msg/RobotDriverState.msg rename to husarion_ugv_msgs/msg/RobotDriverState.msg index 3be5deae8..1b9cc2b02 100644 --- a/husarion_ugv_msg/msg/RobotDriverState.msg +++ b/husarion_ugv_msgs/msg/RobotDriverState.msg @@ -1,6 +1,6 @@ std_msgs/Header header -husarion_ugv_msg/DriverStateNamed[] driver_states +husarion_ugv_msgs/DriverStateNamed[] driver_states bool error bool write_pdo_cmds_error diff --git a/husarion_ugv_msg/msg/RuntimeError.msg b/husarion_ugv_msgs/msg/RuntimeError.msg similarity index 100% rename from husarion_ugv_msg/msg/RuntimeError.msg rename to husarion_ugv_msgs/msg/RuntimeError.msg diff --git a/husarion_ugv_msg/msg/ScriptFlag.msg b/husarion_ugv_msgs/msg/ScriptFlag.msg similarity index 100% rename from husarion_ugv_msg/msg/ScriptFlag.msg rename to husarion_ugv_msgs/msg/ScriptFlag.msg diff --git a/husarion_ugv_msg/msg/SystemStatus.msg b/husarion_ugv_msgs/msg/SystemStatus.msg similarity index 100% rename from husarion_ugv_msg/msg/SystemStatus.msg rename to husarion_ugv_msgs/msg/SystemStatus.msg diff --git a/husarion_ugv_msg/package.xml b/husarion_ugv_msgs/package.xml similarity index 97% rename from husarion_ugv_msg/package.xml rename to husarion_ugv_msgs/package.xml index ae503181a..44d44a1cc 100644 --- a/husarion_ugv_msg/package.xml +++ b/husarion_ugv_msgs/package.xml @@ -1,7 +1,7 @@ - husarion_ugv_msg + husarion_ugv_msgs 2.1.2 Custom messages for Husarion UGV Husarion diff --git a/husarion_ugv_msg/srv/SetLEDAnimation.srv b/husarion_ugv_msgs/srv/SetLEDAnimation.srv similarity index 53% rename from husarion_ugv_msg/srv/SetLEDAnimation.srv rename to husarion_ugv_msgs/srv/SetLEDAnimation.srv index 7234925d4..d3bea5057 100644 --- a/husarion_ugv_msg/srv/SetLEDAnimation.srv +++ b/husarion_ugv_msgs/srv/SetLEDAnimation.srv @@ -1,4 +1,4 @@ -husarion_ugv_msg/LEDAnimation animation +husarion_ugv_msgs/LEDAnimation animation bool repeating --- bool success diff --git a/husarion_ugv_msg/srv/SetLEDBrightness.srv b/husarion_ugv_msgs/srv/SetLEDBrightness.srv similarity index 100% rename from husarion_ugv_msg/srv/SetLEDBrightness.srv rename to husarion_ugv_msgs/srv/SetLEDBrightness.srv diff --git a/husarion_ugv_msgs/srv/SetLEDImageAnimation.srv b/husarion_ugv_msgs/srv/SetLEDImageAnimation.srv new file mode 100644 index 000000000..f429607be --- /dev/null +++ b/husarion_ugv_msgs/srv/SetLEDImageAnimation.srv @@ -0,0 +1,7 @@ +husarion_ugv_msgs/LEDImageAnimation front +husarion_ugv_msgs/LEDImageAnimation rear +bool interrupting +bool repeating +--- +bool success +string message From 0f61d573b7615cd3b5c48f505a3368423c50b5ca Mon Sep 17 00:00:00 2001 From: rafal-gorecki Date: Wed, 11 Dec 2024 15:32:37 +0100 Subject: [PATCH 3/3] fix --- husarion_ugv_msgs/msg/DriverState.msg | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/husarion_ugv_msgs/msg/DriverState.msg b/husarion_ugv_msgs/msg/DriverState.msg index 178e26391..94212d157 100644 --- a/husarion_ugv_msgs/msg/DriverState.msg +++ b/husarion_ugv_msgs/msg/DriverState.msg @@ -3,10 +3,10 @@ float32 current float32 temperature float32 heatsink_temperature -husarion_ugv_interfaces/FaultFlag fault_flag -husarion_ugv_interfaceserfaces/ScriptFlag script_flag -husarion_ugv_interfaceserfaces/RuntimeError channel_1_motor_runtime_error -husarion_ugv_interfaceserfaces/RuntimeError channel_2_motor_runtime_error +husarion_ugv_msgs/FaultFlag fault_flag +husarion_ugv_msgs/ScriptFlag script_flag +husarion_ugv_msgs/RuntimeError channel_1_motor_runtime_error +husarion_ugv_msgs/RuntimeError channel_2_motor_runtime_error bool motor_states_data_timed_out bool driver_state_data_timed_out