diff --git a/.docs/panther_ros2_api.drawio.svg b/.docs/panther_ros2_api.drawio.svg deleted file mode 100644 index 19f5bf614..000000000 --- a/.docs/panther_ros2_api.drawio.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - -panther_localizationpanther_localizationpanther_controllerpanther_controllerpanther_lightspanther_lightspanther_hardware_interfacespanther_hardware_interfacespanther_batterypanther_batterypanther_managerpanther_managerpanther_diagnosticspanther_diagnosticsPantherSystemPantherSystemhardware_controllerhardware_controllerGPIOControllerGPIOControllerMotorsControllerMotorsControllerCANopenControllerCANopenControllerRoboteqDriverRoboteqDriverCANCANEStopManagerEStopManagerbattery_driverbattery_driverRPi GPIORPi GPIOADCADCimu_broadcasterimu_broadcasterjoint_state_broadcasterjoint_state_broadcasterdrive_controllerdrive_controllercontroller_managercontroller_managerPantherImuSensorPantherImuSensor IMUIMUekf_filterekf_filterImuFilterImuFilterSpatialSpatialimu/dataimu/dataodometry/wheelsodometry/wheelsodometry/filteredodometry/filteredjoint_statesjoint_statescmd_velcmd_veldynamic_joint_statesdynamic_joint_states hardware/e_stop hardware/e_stophardware/robot_driver_statehardware/robot_driver_state hardware/io_state hardware/io_statehardware/e_stop_triggerhardware/e_stop_triggerhardware/e_stop_resethardware/e_stop_resethardware/<hw_component>_enablehardware/<hw_component>_enablerobot_state_publisherrobot_state_publisherrobot_descriptionrobot_description/tf/tf/tf_static/tf_static/tf/tfbattery/battery_statusbattery/battery_statusBumper LightsBumper Lights lights_driverlights_driverlights_controllerlights_controllerlights/channel_1_framelights/channel_1_framelights/channel_2_framelights/channel_2_framelights/set_animationlights/set_animationlights/set_brightnesslights/set_brightness safety_managersafety_managersystem_monitorsystem_monitorsystem_statussystem_statuslights_managerlights_managerhardware/led_control_enablehardware/led_control_enable/tf/tfbattery/charging_statusbattery/charging_statusGPIODriverGPIODriverdiagnosticsdiagnosticsdiagnosticsdiagnosticsdiagnosticsdiagnostics diagnosticsdiagnosticsLegend:Legend:NodesNodesPluginPluginObjectsObjectsTopicsTopicsServicesServicesData TransferData Trans...Text is not SVG - cannot display diff --git a/.docs/ros2_system_design.drawio.svg b/.docs/ros2_system_design.drawio.svg new file mode 100644 index 000000000..ee8bfd806 --- /dev/null +++ b/.docs/ros2_system_design.drawio.svg @@ -0,0 +1,4 @@ + + + +husarion_ugv_localizationhusarion_ugv_localizationhusarion_ugv_controllerhusarion_ugv_controllerhusarion_ugv_lightshusarion_ugv_lightshusarion_ugv_hardware_interfaceshusarion_ugv_hardware_interfaceshusarion_ugv_batteryhusarion_ugv_batteryhusarion_ugv_managerhusarion_ugv_managerhusarion_ugv_diagnosticshusarion_ugv_diagnosticsHusarionUGVSystemHusarionUGVSystemhardware_controllerhardware_controllerGPIOControllerGPIOControllerMotorsControllerMotorsControllerCANopenControllerCANopenControllerRoboteqDriverRoboteqDriverCANCANEStopManagerEStopManagerbattery_driverbattery_driverRPi GPIORPi GPIOADCADCimu_broadcasterimu_broadcasterjoint_state_broadcasterjoint_state_broadcasterdrive_controllerdrive_controllercontroller_managercontroller_managerHusarionUGVImuSensorHusarionUGVImuSensor IMUIMUekf_filterekf_filterImuFilterImuFilterSpatialSpatialimu/dataimu/dataodometry/wheelsodometry/wheelsodometry/filteredodometry/filteredjoint_statesjoint_statescmd_velcmd_veldynamic_joint_statesdynamic_joint_states hardware/e_stop hardware/e_stophardware/robot_driver_statehardware/robot_driver_state hardware/io_state hardware/io_statehardware/e_stop_triggerhardware/e_stop_triggerhardware/e_stop_resethardware/e_stop_resethardware/<hw_component>_enablehardware/<hw_component>_enablerobot_state_publisherrobot_state_publisherrobot_descriptionrobot_description/tf/tf/tf_static/tf_static/tf/tfbattery/battery_statusbattery/battery_statusBumper LightsBumper Lights lights_driverlights_driverlights_controllerlights_controllerlights/channel_1_framelights/channel_1_framelights/channel_2_framelights/channel_2_framelights/set_animationlights/set_animationlights/set_brightnesslights/set_brightness safety_managersafety_managersystem_monitorsystem_monitorsystem_statussystem_statuslights_managerlights_managerhardware/led_control_enablehardware/led_control_enable/tf/tfbattery/charging_statusbattery/charging_statusGPIODriverGPIODriverdiagnosticsdiagnosticsdiagnosticsdiagnosticsdiagnosticsdiagnostics diagnosticsdiagnosticsLegend:Legend:NodesNodesPluginPluginObjectsObjectsTopicsTopicsServicesServicesData TransferData Trans...Text is not SVG - cannot display diff --git a/.github/workflows/release-project.yaml b/.github/workflows/release-project.yaml index 47800b4f5..8bdbcade4 100644 --- a/.github/workflows/release-project.yaml +++ b/.github/workflows/release-project.yaml @@ -1,5 +1,5 @@ --- -name: Release Panther project +name: Release project on: workflow_dispatch: diff --git a/.github/workflows/run-unit-tests.yaml b/.github/workflows/run-unit-tests.yaml index 6d7d48783..48c1ebf69 100644 --- a/.github/workflows/run-unit-tests.yaml +++ b/.github/workflows/run-unit-tests.yaml @@ -1,5 +1,5 @@ --- -name: Run panther unit tests +name: Run unit tests on: workflow_dispatch: @@ -28,12 +28,12 @@ jobs: uses: actions/checkout@v3 with: ref: ${{ github.ref }} - path: ros2_ws/src/panther_ros + path: ros2_ws/src/husarion_ugv - name: Resolve dependencies working-directory: ros2_ws run: | - vcs import < src/panther_ros/panther/panther_hardware.repos src + vcs import < src/husarion_ugv/husarion_ugv/hardware_deps.repos src sudo apt update rosdep update --rosdistro $ROS_DISTRO rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y @@ -43,15 +43,15 @@ jobs: run: | source /opt/ros/$ROS_DISTRO/setup.bash if [ -f install/setup.bash ]; then source install/setup.bash; fi - colcon build --symlink-install --parallel-workers $(nproc) --packages-up-to panther --cmake-args -DCMAKE_CXX_FLAGS='-fprofile-arcs -ftest-coverage' + colcon build --symlink-install --parallel-workers $(nproc) --packages-up-to husarion_ugv --cmake-args -DCMAKE_CXX_FLAGS='-fprofile-arcs -ftest-coverage' - name: Test working-directory: ros2_ws run: | source install/setup.bash - colcon test --packages-up-to panther --retest-until-pass 10 --event-handlers console_cohesion+ --return-code-on-test-failure + colcon test --packages-up-to husarion_ugv --retest-until-pass 10 --event-handlers console_cohesion+ --return-code-on-test-failure echo "result=$?" >> ${{ runner.temp }}/${{ env.TEST_RESULT_FILENAME }} - colcon lcov-result --packages-up-to panther --verbose >> ${{ runner.temp }}/${{ env.COVERAGE_RESULT_FILENAME }} + colcon lcov-result --packages-up-to husarion_ugv --verbose >> ${{ runner.temp }}/${{ env.COVERAGE_RESULT_FILENAME }} lines_cov=$(cat ${{ runner.temp }}/${{ env.COVERAGE_RESULT_FILENAME }} | grep -E 'lines' | head -1) functions_cov=$(cat ${{ runner.temp }}/${{ env.COVERAGE_RESULT_FILENAME }} | grep -E 'functions' | head -1) branches_cov=$(cat ${{ runner.temp }}/${{ env.COVERAGE_RESULT_FILENAME }} | grep -E 'branches' | head -1) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index c426d2101..a685e4f18 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -47,7 +47,7 @@ repos: entry: codespell args: [ - "--exclude-file=panther_hardware_interfaces/config/roboteq_motor_controllers_v80_21a.eds", + "--exclude-file=husarion_ugv_hardware_interfaces/config/roboteq_motor_controllers_v80_21a.eds", "--ignore-words-list", "ned" # north, east, down (NED) ] diff --git a/README.md b/README.md index e887b3cb9..d60fca406 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ -# panther_ros +# husarion_ugv -ROS 2 packages for Panther autonomous mobile robot +ROS 2 packages for Husarion UGV (Unmanned Ground Vehicle). The repository is a collection of necessary packages enabling the launch of the Lynx and Panther robots. [![pre-commit](https://img.shields.io/badge/pre--commit-enabled-brightgreen?logo=pre-commit)](https://github.com/pre-commit/pre-commit) @@ -16,7 +16,7 @@ ROS 2 packages for Panther autonomous mobile robot ```bash mkdir ~/husarion_ws cd ~/husarion_ws -git clone -b ros2 https://github.com/husarion/panther_ros.git src/panther_ros +git clone -b ros2 https://github.com/husarion/panther_ros.git src/husarion_ugv ``` ### Configure environment @@ -38,7 +38,7 @@ export HUSARION_ROS_BUILD_TYPE=simulation ### Build ``` bash -vcs import src < src/panther_ros/panther/panther_$HUSARION_ROS_BUILD_TYPE.repos +vcs import src < src/husarion_ugv/husarion_ugv/${HUSARION_ROS_BUILD_TYPE}_deps.repos cp -r src/ros2_controllers/diff_drive_controller src cp -r src/ros2_controllers/imu_sensor_broadcaster src @@ -49,26 +49,26 @@ rosdep update --rosdistro $ROS_DISTRO rosdep install --from-paths src -y -i source /opt/ros/$ROS_DISTRO/setup.bash -colcon build --symlink-install --packages-up-to panther --cmake-args -DCMAKE_BUILD_TYPE=Release +colcon build --symlink-install --packages-up-to husarion_ugv --cmake-args -DCMAKE_BUILD_TYPE=Release source install/setup.bash ``` >[!NOTE] -> To build code on a real robot you need to run above commands on the Panther Built-in Computer. +> To build code on a real robot you need to run above commands on the robot Built-in Computer. ### Running Real robot: ```bash -ros2 launch panther_bringup bringup.launch.py +ros2 launch husarion_ugv_bringup bringup.launch.py ``` Simulation: ```bash -ros2 launch panther_gazebo simulation.launch.py +ros2 launch husarion_ugv_gazebo simulation.launch.py ``` > [!IMPORTANT] @@ -87,26 +87,26 @@ Launch arguments are largely common to both simulation and physical robot. Howev | --- | ---------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | 🖥️ | `add_wheel_joints` | Flag enabling joint_state_publisher to publish information about the wheel position. Should be false when there is a controller that sends this information. ***bool:*** `False` | | 🖥️ | `add_world_transform` | Adds a world frame that connects the tf trees of individual robots (useful when running multiple robots). ***bool:*** `False` | -| 🤖🖥️ | `animations_config_path` | Path to a YAML file with a description of led configuration. This file includes definition of robot panels, virtual segments and default animations. ***string:*** [`led_config.yaml`](./panther_lights/config/led_config.yaml) | +| 🤖🖥️ | `animations_config_path` | Path to a YAML file with a description of led configuration. This file includes definition of robot panels, virtual segments and default animations. ***string:*** [`{robot_model}_animations.yaml`](./husarion_ugv_lights/config) | | 🖥️ | `battery_config_path` | Path to the Ignition LinearBatteryPlugin configuration file. This configuration is intended for use in simulations only. ***string:*** `None` | -| 🤖🖥️ | `components_config_path` | Additional components configuration file. Components described in this file are dynamically included in Panther's urdf. Panther options are described in [the manual](https://husarion.com/manuals/panther/panther-options). ***string:*** [`components.yaml`](./panther_description/config/components.yaml) | -| 🤖🖥️ | `controller_config_path` | Path to controller configuration file. A path to custom configuration can be specified here. ***string:*** [`{wheel_type}_controller.yaml`](./panther_controller/config/) | +| 🤖🖥️ | `components_config_path` | Additional components configuration file. Components described in this file are dynamically included in robot's URDF. Available options are described in [the manual](https://husarion.com/manuals/panther/panther-options). ***string:*** [`components.yaml`](./panther_description/config/components.yaml) | +| 🤖🖥️ | `controller_config_path` | Path to controller configuration file. A path to custom configuration can be specified here. ***string:*** [`{wheel_type}_controller.yaml`](./husarion_ugv_controller/config/) | | 🤖 | `disable_manager` | Enable or disable manager_bt_node. ***bool:*** `False` | | 🤖🖥️ | `fuse_gps` | Include GPS for data fusion. ***bool:*** `False` | -| 🖥️ | `gz_bridge_config_path` | Path to the parameter_bridge configuration file. ***string:*** [`gz_bridge.yaml`](./panther_gazebo/config/gz_bridge.yaml) | +| 🖥️ | `gz_bridge_config_path` | Path to the parameter_bridge configuration file. ***string:*** [`gz_bridge.yaml`](./husarion_ugv_gazebo/config/gz_bridge.yaml) | | 🖥️ | `gz_gui` | Run simulation with specific GUI layout. ***string:*** [`teleop.config`](https://github.com/husarion/husarion_gz_worlds/blob/main/config/teleop.config) | | 🖥️ | `gz_headless_mode` | Run the simulation in headless mode. Useful when a GUI is not needed or to reduce the number of calculations. ***bool:*** `False` | | 🖥️ | `gz_log_level` | Adjust the level of console output. ***int:*** `1` (choices: `0`, `1`, `2`, `3`, `4`) | | 🖥️ | `gz_world` | Absolute path to SDF world file. ***string:*** [`husarion_world.sdf`](https://github.com/husarion/husarion_gz_worlds/blob/main/worlds/husarion_world.sdf) | | 🤖 | `launch_nmea_gps` | Whether to launch the NMEA NavSat driver node. Advisable when the robot is equipped with the [ANT02](https://husarion.com/manuals/panther/panther-options/#ant02---wi-fi--lte--gps). ***bool:*** `False` | -| 🤖🖥️ | `lights_bt_project_path` | Path to BehaviorTree project file, responsible for lights management. ***string:*** [`PantherLightsBT.btproj`](./panther_manager/behavior_trees/PantherLightsBT.btproj) | -| 🤖🖥️ | `localization_config_path` | Specify the path to the localization configuration file. ***string:*** [`relative_localization.yaml`](./panther_localization/config/relative_localization.yaml) | +| 🤖🖥️ | `lights_bt_project_path` | Path to BehaviorTree project file, responsible for lights management. ***string:*** [`PantherLightsBT.btproj`](./husarion_ugv_manager/behavior_trees/PantherLightsBT.btproj) | +| 🤖🖥️ | `localization_config_path` | Specify the path to the localization configuration file. ***string:*** [`relative_localization.yaml`](./husarion_ugv_localization/config/relative_localization.yaml) | | 🤖🖥️ | `localization_mode` | Specifies the localization mode: - 'relative' `odometry/filtered` data is relative to the initial position and orientation. - 'enu' `odometry/filtered` data is relative to initial position and ENU (East North Up) orientation. ***string:*** `relative` (choices: `relative`, `enu`) | | 🤖🖥️ | `namespace` | Add namespace to all launched nodes. ***string:*** `env(ROBOT_NAMESPACE)` | -| 🤖🖥️ | `publish_robot_state` | Whether to publish the default Panther robot description. ***bool:*** `True` | -| 🖥️ | `robot_model` | Specify robot model type. ***string:*** `env(ROBOT_MODEL)` if not specified `panther` (choices: `lynx`, `panther`) | -| 🤖🖥️ | `safety_bt_project_path` | Path to BehaviorTree project file, responsible for safety and shutdown management. ***string:*** [`PantherSafetyBT.btproj`](./panther_manager/behavior_trees/PantherSafetyBT.btproj) | -| 🤖🖥️ | `shutdown_hosts_config_path` | Path to file with list of hosts to request shutdown. ***string:*** [`shutdown_hosts_config.yaml`](./panther_manager/config/shutdown_hosts_config.yaml) | +| 🤖🖥️ | `publish_robot_state` | Whether to publish the default URDF of specified robot. ***bool:*** `True` | +| 🖥️ | `robot_model` | Specify robot model type. ***string:*** `env(ROBOT_MODEL)` (choices: `lynx`, `panther`) | +| 🤖🖥️ | `safety_bt_project_path` | Path to BehaviorTree project file, responsible for safety and shutdown management. ***string:*** [`PantherSafetyBT.btproj`](./husarion_ugv_manager/behavior_trees/PantherSafetyBT.btproj) | +| 🤖🖥️ | `shutdown_hosts_config_path` | Path to file with list of hosts to request shutdown. ***string:*** [`shutdown_hosts.yaml`](./husarion_ugv_manager/config/shutdown_hosts.yaml) | | 🤖🖥️ | `use_ekf` | Enable or disable EKF. ***bool:*** `True` | | 🤖🖥️ | `use_sim` | Whether simulation is used. ***bool:*** `False` | | 🤖🖥️ | `user_led_animations_path` | Path to a YAML file with a description of the user-defined animations. ***string:*** `''` | @@ -121,7 +121,7 @@ Launch arguments are largely common to both simulation and physical robot. Howev > [!TIP] > -> To read the arguments for individual packages, add the `-s` flag to the `ros2 launch` command (e.g. `ros2 launch panther_bringup bringup.launch.py -s`) +> To read the arguments for individual packages, add the `-s` flag to the `ros2 launch` command (e.g. `ros2 launch husarion_ugv_bringup bringup.launch.py -s`) ## Developer Info diff --git a/ROS_API.md b/ROS_API.md index e7fb79a60..6a2be282c 100644 --- a/ROS_API.md +++ b/ROS_API.md @@ -3,7 +3,7 @@ > [!IMPORTANT] > **Beta Release** > -> Please be advised that the software you are about to use is a Beta version of the ROS 2 Driver for Panther. It is functional, and the architecture will not change significantly. Although it has been tested by the Husarion team, some stability issues and bugs may still occur. +> Please be advised that the software you are about to use is a Beta version of the ROS 2 Driver for Lynx and Panther. It is functional, and the architecture will not change significantly. Although it has been tested by the Husarion team, some stability issues and bugs may still occur. > > We would greatly appreciate your feedback regarding the Panther ROS 2 driver. You can reach us in the following ways: > @@ -13,20 +13,20 @@ ## ROS 2 System Design -This section describes the ROS packages in the Panther ROS system. These packages are located in the [panther_ros](https://github.com/husarion/panther_ros) GitHub repository. +This section describes the ROS packages used in Husarion UGV robots. These packages are located in the [panther_ros](https://github.com/husarion/panther_ros) GitHub repository. > [!NOTE] -> **Differences in ROS System** +> **Hardware Compatibility** > -> ROS 2 nodes differs slightly between **Panther v1.06** and **Panther v1.2+**. This is caused by internal hardware differences. Despite that, the ROS API was kept as closely matched between those revisions as possible and should be transparent in most of the use cases. +> This package supports **Lynx v0.2**, **Panther v1.2+**. This is caused by internal hardware differences. Despite that, the ROS API was kept as closely matched between those revisions as possible and should be transparent in most of the use cases. -The default way to communicate with Panther's hardware is via the Robot Operating System (ROS). All the drivers were written in ROS 2 framework. The ROS API is provided by ROS packages found in the GitHub repository [husarion/panther_ros](https://github.com/husarion/panther_ros). These packages are responsible for accessing the hardware components of the robot. +The default way to communicate with our robots is via the Robot Operating System (ROS). All the drivers were written in ROS 2 framework. The ROS API is provided by ROS packages found in the GitHub repository [husarion/panther_ros](https://github.com/husarion/panther_ros). These packages are responsible for accessing the hardware components of the robot. -The graph below represents Panther's ROS system. Some topics and services have been excluded from the graph for the sake of clarity. +The graph below represents Husarion UVG ROS system. Some topics and services have been excluded from the graph for the sake of clarity. -![Panther ROS 2 API Diagram](.docs/panther_ros2_api.drawio.svg) +![Husarion UVG ROS 2 System Design Diagram](.docs/ros2_system_design.drawio.svg) ## ROS Interfaces @@ -42,31 +42,31 @@ Below is information about the physical robot API. For the simulation, topics an | | Node name | Description | | --- | ------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| 🤖 | `battery_driver` | Publishes battery state read from ADC unit for Panther version 1.2 and above, or based on Roboteq motor controllers' data for earlier versions of the robot. [*panther_batter/battery_driver_node*](./panther_battery/include/panther_battery/battery_driver_node.hpp) | +| 🤖 | `battery_driver` | Publishes battery state read from ADC unit. [*panther_batter/battery_driver_node*](./husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp) | | 🤖🖥️ | `controller_manager` | The Controller Manager performs two main functions. First, it manages controllers and their required interfaces, handling tasks like loading, activating, deactivating, and unloading. Second, it interacts with hardware components, ensuring access to their interfaces. This node manages the: `imu_broadcaster`, `joint_state_broadcaster`, `drive_controller`. *[controller_manager/controller_manager](https://github.com/ros-controls/ros2_control/blob/master/controller_manager)* | | 🤖🖥️ | `drive_controller` | Manages mobile robots with a differential or mecanum drive depending on the configuration. It converts velocity commands for the robot body into wheel commands for the base. It also calculates odometry from hardware feedback and shares it. *[diff_drive_controller/diff_drive_controller](https://github.com/ros-controls/ros2_controllers/tree/master/diff_drive_controller) or [mecanum_drive_controller/mecanum_drive_controller](https://github.com/husarion/husarion_controllers/tree/main/mecanum_drive_controller)* | | 🤖🖥️ | `ekf_filter` | The Extended Kalman Filter node is designed to fuse odometry data from various sources, including wheel encoders, IMU, and GPS. *[robot_localization/ekf_filter](https://github.com/cra-ros-pkg/robot_localization)* | -| 🤖 | `hardware_controller` | Plugin responsible for communicating with engine controllers via the CAN bus and providing E-Stop functionalities. *[panther_hardware_interfaces/PantherSystem](./panther_hardware_interfaces/src/panther_system/)* | +| 🤖 | `hardware_controller` | Plugin responsible for communicating with engine controllers via the CAN bus and providing E-Stop functionalities. *[husarion_ugv_hardware_interfaces/{robot_model}System](./husarion_ugv_hardware_interfaces/src/robot_system/)* | | 🤖 | `gps` | Node responsible for parsing NMEA strings and publishing standard ROS NavSat message types. *[nmea_navsat_driver/nmea_navsat_driver](https://github.com/ros-drivers/nmea_navsat_driver/tree/ros2/src/libnmea_navsat_driver)* | | 🖥️ | `gz_ros2_control` | Responsible for integrating the ros2_control controller architecture with the Gazebo simulator. [gz_ros2_control/gz_ros2_control](https://github.com/ros-controls/gz_ros2_control/tree/master/gz_ros2_control/src) | -| 🖥️ | `gz_estop_gui` | The node is part of the Gazebo GUI plugin, enabling easy E-stop state modifications directly within the simulation. [panther_gazebo/EStop](./panther_gazebo/src/gui/e_stop.cpp) | +| 🖥️ | `gz_estop_gui` | The node is part of the Gazebo GUI plugin, enabling easy E-stop state modifications directly within the simulation. [husarion_ugv_gazebo/EStop](./husarion_ugv_gazebo/src/gui/e_stop.cpp) | | 🤖🖥️ | `imu_broadcaster` | Publishes readings of IMU sensors. *[imu_sensor_broadcaster/imu_sensor_broadcaster](https://github.com/ros-controls/ros2_controllers/tree/master/imu_sensor_broadcaster)* | | 🤖🖥️ | `joint_state_broadcaster` | Reads all state interfaces and reports them on specific topics. *[joint_state_broadcaster/joint_state_broadcaster](https://github.com/ros-controls/ros2_controllers/tree/master/joint_state_broadcaster)* | | 🤖🖥️ | `lights_container` | Node for managing ROS components. This node manages: `lights_controller`, `lights_driver`. [*rclcpp_components/component_container*](https://github.com/ros2/rclcpp/tree/rolling/rclcpp_components) | -| 🤖🖥️ | `lights_controller` | This node is responsible for processing animations and publishing frames to be displayed on the Husarion Panther robot Bumper Lights. [*panther_lights/LightsControllerNode*](./panther_lights/include/panther_lights/lights_controller_node.hpp) | -| 🤖 | `lights_driver` | This node is responsible for displaying frames on the Husarion Panther robot's Bumper Lights. [*panther_lights/LightsDriverNode*](./panther_lights/include/panther_lights/lights_driver_node.hpp) | -| 🤖🖥️ | `lights_manager` | Node responsible for managing Bumper Lights animation scheduling. [panther_manager/lights_manager](./panther_manager/include/panther_manager/lights_manager_node.hpp) | +| 🤖🖥️ | `lights_controller` | This node is responsible for processing animations and publishing frames to `light_driver` node. [*husarion_ugv_lights/LightsControllerNode*](./husarion_ugv_lights/include/husarion_ugv_lights/lights_controller_node.hpp) | +| 🤖 | `lights_driver` | This node is responsible for displaying frames on the robot's lights. [*husarion_ugv_lights/LightsDriverNode*](./husarion_ugv_lights/include/husarion_ugv_lights/lights_driver_node.hpp) | +| 🤖🖥️ | `lights_manager` | Node responsible for managing lights animation scheduling. [husarion_ugv_manager/lights_manager](./husarion_ugv_manager/include/husarion_ugv_manager/lights_manager_node.hpp) | | 🤖🖥️⚙️ | `navsat_transform` | It converts raw GPS data into odometry data and publishes corrected GPS positions based on sensor data at a higher frequency. *[robot_localization/navsat_transform](https://github.com/cra-ros-pkg/robot_localization)* | -| 🖥️ | `panther_base_gz_bridge` | Convert and transmit data between ROS and Gazebo *[ros_gz_bridge/parameter_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge)* | +| 🖥️ | `base_gz_bridge` | Convert and transmit data between ROS and Gazebo *[ros_gz_bridge/parameter_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge)* | | 🤖🖥️ | `robot_state_publisher` | Broadcasts a robot's state to tf2 using a provided URDF model and joint states. It updates the model and broadcasts poses for fixed and movable joints to tf2 topics. *[robot_state_publisher/robot_state_publisher](https://github.com/ros/robot_state_publisher)* | -| 🤖 | `safety_manager` | Node responsible for managing safety features, and software shutdown of components. *[panther_manager/safety_manager_node](./panther_manager/include/panther_manager/safety_manager_node.hpp)* | -| 🤖 | `system_monitor` | Publishes system state of the Built-in Computer such as CPU usage, RAM memory usage, disk usage and CPU temperature. *[panther_diagnostic/system_monitor_node](./panther_diagnostics/include/panther_diagnostics/system_monitor_node.hpp)* | +| 🤖 | `safety_manager` | Node responsible for managing safety features, and software shutdown of components. *[husarion_ugv_manager/safety_manager_node](./husarion_ugv_manager/include/husarion_ugv_manager/safety_manager_node.hpp)* | +| 🤖 | `system_monitor` | Publishes system state of the Built-in Computer such as CPU usage, RAM memory usage, disk usage and CPU temperature. *[husarion_ugv_diagnostics/system_monitor_node](./husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp)* | ### Topics | | Topic | Description | | --- | ---------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| 🤖🖥️ | `battery/battery_status` | Mean values of both batteries if Panther has two batteries. Otherwise, the state of the single battery will be published. [*sensor_msgs/BatteryState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/BatteryState.html) | +| 🤖🖥️ | `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) | | 🤖🖥️ | `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) | diff --git a/panther/CHANGELOG.rst b/husarion_ugv/CHANGELOG.rst similarity index 100% rename from panther/CHANGELOG.rst rename to husarion_ugv/CHANGELOG.rst diff --git a/panther/CMakeLists.txt b/husarion_ugv/CMakeLists.txt similarity index 80% rename from panther/CMakeLists.txt rename to husarion_ugv/CMakeLists.txt index 626fc36ab..2c2d0e254 100644 --- a/panther/CMakeLists.txt +++ b/husarion_ugv/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(panther) +project(husarion_ugv) find_package(ament_cmake REQUIRED) diff --git a/husarion_ugv/README.md b/husarion_ugv/README.md new file mode 100644 index 000000000..bc079c16b --- /dev/null +++ b/husarion_ugv/README.md @@ -0,0 +1,3 @@ +# husarion_ugv + +ROS 2 Metapackage composing basic functionalities of the Husarion UGV robot with VCS Tool yaml files directing to external robot dependencies. diff --git a/panther/panther_hardware.repos b/husarion_ugv/hardware_deps.repos similarity index 100% rename from panther/panther_hardware.repos rename to husarion_ugv/hardware_deps.repos diff --git a/panther/package.xml b/husarion_ugv/package.xml similarity index 71% rename from panther/package.xml rename to husarion_ugv/package.xml index f849f5671..e426e3876 100644 --- a/panther/package.xml +++ b/husarion_ugv/package.xml @@ -1,9 +1,9 @@ - panther + husarion_ugv 2.1.1 - Meta package that contains all packages of Panther + Meta package that contains all packages of Husarion UGV (Unmanned Ground Vehicle) Husarion Apache License 2.0 @@ -15,8 +15,8 @@ ament_cmake - panther_bringup - panther_gazebo + husarion_ugv_bringup + husarion_ugv_gazebo ament_cmake diff --git a/panther/panther_simulation.repos b/husarion_ugv/simulation_deps.repos similarity index 100% rename from panther/panther_simulation.repos rename to husarion_ugv/simulation_deps.repos diff --git a/panther_battery/CHANGELOG.rst b/husarion_ugv_battery/CHANGELOG.rst similarity index 100% rename from panther_battery/CHANGELOG.rst rename to husarion_ugv_battery/CHANGELOG.rst diff --git a/panther_battery/CMakeLists.txt b/husarion_ugv_battery/CMakeLists.txt similarity index 97% rename from panther_battery/CMakeLists.txt rename to husarion_ugv_battery/CMakeLists.txt index 4e12bab87..d928de579 100644 --- a/panther_battery/CMakeLists.txt +++ b/husarion_ugv_battery/CMakeLists.txt @@ -1,18 +1,18 @@ cmake_minimum_required(VERSION 3.10.2) -project(panther_battery) +project(husarion_ugv_battery) 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 - panther_utils rclcpp sensor_msgs) + husarion_ugv_utils rclcpp sensor_msgs) foreach(PACKAGE IN ITEMS ${PACKAGE_DEPENDENCIES}) find_package(${PACKAGE} REQUIRED) endforeach() -include_directories(include ${panther_utils_INCLUDE_DIRS}) +include_directories(include ${husarion_ugv_utils_INCLUDE_DIRS}) add_executable( battery_driver_node diff --git a/panther_battery/README.md b/husarion_ugv_battery/README.md similarity index 75% rename from panther_battery/README.md rename to husarion_ugv_battery/README.md index d591938d3..1e2e0b846 100644 --- a/panther_battery/README.md +++ b/husarion_ugv_battery/README.md @@ -1,6 +1,6 @@ -# panther_battery +# husarion_ugv_battery -The package containing nodes monitoring and publishing the internal battery state of the Husarion Panther robot. +The package containing nodes monitoring and publishing the internal battery state of the Husarion UGV robots. ## Launch Files @@ -12,13 +12,13 @@ This package contains: ### battery_driver_node -Publishes battery state read from ADC unit for Panther version 1.2 and above, or based on Roboteq motor controllers' data for earlier.versions of the robot. +Publishes battery state read from ADC unit. #### Publishes - `_battery/battery_1_status_raw` [*sensor_msgs/BatteryState*]: First battery raw state. - `_battery/battery_2_status_raw` [*sensor_msgs/BatteryState*]: Second battery raw state. Published if second battery detected. -- `battery/battery_status` [*sensor_msgs/BatteryState*]: Mean values of both batteries if Panther has two batteries. Otherwise, the state of the single battery will be published. +- `battery/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. - `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: Battery diagnostic messages. @@ -29,11 +29,11 @@ Publishes battery state read from ADC unit for Panther version 1.2 and above, or #### Parameters -- `~/adc/device0` [*string*, default: **/sys/bus/iio/devices/iio:device0**]: ADC nr 0 IIO device. Used with Panther version 1.2 and above. -- `~/adc/device1` [*string*, default: **/sys/bus/iio/devices/iio:device1**]: ADC nr 1 IIO device. Used with Panther version 1.2 and above. -- `~/adc/ma_window_len/charge` [*int*, default: **10**]: Window length of a moving average, used to smooth out battery charge readings. Used with Panther version 1.2 and above. -- `~/adc/ma_window_len/temp` [*int*, default: **10**]: Window length of a moving average, used to smooth out battery temperature readings. Used with Panther version 1.2 and above. +- `~/adc/device0` [*string*, default: **/sys/bus/iio/devices/iio:device0**]: ADC number 0 IIO device. +- `~/adc/device1` [*string*, default: **/sys/bus/iio/devices/iio:device1**]: ADC number 1 IIO device. +- `~/adc/ma_window_len/charge` [*int*, default: **10**]: Window length of a moving average, used to smooth out battery charge readings. +- `~/adc/ma_window_len/temp` [*int*, default: **10**]: Window length of a moving average, used to smooth out battery temperature readings. - `~/battery_timeout` [*float*, default: **1.0**]: Specifies the timeout in seconds. If the node fails to read battery data exceeding this duration, the node will publish an unknown battery state. - `~/ma_window_len/voltage` [*int*, default: **10**]: Window length of a moving average, used to smooth out battery voltage readings. - `~/ma_window_len/current` [*int*, default: **10**]: Window length of a moving average, used to smooth out battery current readings. -- `~/roboteq/driver_state_timeout` [*float*, default: **0.2**]: Specifies timeout in seconds after which driver state messages will be considered old. Used with Panther version 1.06 and earlier. +- `~/roboteq/driver_state_timeout` [*float*, default: **0.2**]: Specifies timeout in seconds after which driver state messages will be considered old (deprecated). diff --git a/panther_battery/include/panther_battery/adc_data_reader.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/adc_data_reader.hpp similarity index 90% rename from panther_battery/include/panther_battery/adc_data_reader.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/adc_data_reader.hpp index 08dca0d00..59e1fb57e 100644 --- a/panther_battery/include/panther_battery/adc_data_reader.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/adc_data_reader.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_ADC_DATA_READER_HPP_ -#define PANTHER_BATTERY_ADC_DATA_READER_HPP_ +#ifndef HUSARION_UGV_BATTERY_ADC_DATA_READER_HPP_ +#define HUSARION_UGV_BATTERY_ADC_DATA_READER_HPP_ #include #include #include #include -namespace panther_battery +namespace husarion_ugv_battery { class ADCDataReader @@ -75,6 +75,6 @@ class ADCDataReader const std::filesystem::path device_path_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_ADC_DATA_READER_HPP_ +#endif // HUSARION_UGV_BATTERY_ADC_DATA_READER_HPP_ diff --git a/panther_battery/include/panther_battery/battery/adc_battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/adc_battery.hpp similarity index 83% rename from panther_battery/include/panther_battery/battery/adc_battery.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery/adc_battery.hpp index 6aebfa097..94dd428d4 100644 --- a/panther_battery/include/panther_battery/battery/adc_battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/adc_battery.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_ADC_BATTERY_HPP_ -#define PANTHER_BATTERY_BATTERY_ADC_BATTERY_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_ADC_BATTERY_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_ADC_BATTERY_HPP_ #include #include @@ -21,10 +21,10 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_utils/moving_average.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_utils/moving_average.hpp" -namespace panther_battery +namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; @@ -89,12 +89,12 @@ class ADCBattery : public Battery const std::function ReadTemp; const std::function ReadCharge; - std::unique_ptr> voltage_ma_; - std::unique_ptr> current_ma_; - std::unique_ptr> temp_ma_; - std::unique_ptr> charge_ma_; + std::unique_ptr> voltage_ma_; + std::unique_ptr> current_ma_; + std::unique_ptr> temp_ma_; + std::unique_ptr> charge_ma_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_ADC_BATTERY_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_ADC_BATTERY_HPP_ diff --git a/panther_battery/include/panther_battery/battery/battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp similarity index 95% rename from panther_battery/include/panther_battery/battery/battery.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp index eb067aa61..7e461cfa4 100644 --- a/panther_battery/include/panther_battery/battery/battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/battery.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_BATTERY_HPP_ -#define PANTHER_BATTERY_BATTERY_BATTERY_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_BATTERY_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_BATTERY_HPP_ #include #include @@ -27,7 +27,7 @@ #include "panther_msgs/msg/charging_status.hpp" -namespace panther_battery +namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; @@ -127,6 +127,6 @@ class Battery ChargingStatusMsg charging_status_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_BATTERY_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_BATTERY_HPP_ diff --git a/panther_battery/include/panther_battery/battery/roboteq_battery.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp similarity index 81% rename from panther_battery/include/panther_battery/battery/roboteq_battery.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp index 34d1d3cdd..0b785f79f 100644 --- a/panther_battery/include/panther_battery/battery/roboteq_battery.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery/roboteq_battery.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_ROBOTEQ_BATTERY_HPP_ -#define PANTHER_BATTERY_BATTERY_ROBOTEQ_BATTERY_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_ROBOTEQ_BATTERY_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_ROBOTEQ_BATTERY_HPP_ #include #include @@ -24,10 +24,10 @@ #include "panther_msgs/msg/driver_state_named.hpp" #include "panther_msgs/msg/robot_driver_state.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_utils/moving_average.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_utils/moving_average.hpp" -namespace panther_battery +namespace husarion_ugv_battery { using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; @@ -73,10 +73,10 @@ class RoboteqBattery : public Battery float current_raw_; RobotDriverStateMsg::SharedPtr driver_state_; - std::unique_ptr> voltage_ma_; - std::unique_ptr> current_ma_; + std::unique_ptr> voltage_ma_; + std::unique_ptr> current_ma_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_ROBOTEQ_BATTERY_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_ROBOTEQ_BATTERY_HPP_ diff --git a/panther_battery/include/panther_battery/battery_driver_node.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp similarity index 80% rename from panther_battery/include/panther_battery/battery_driver_node.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp index 0832bc038..1bba8b993 100644 --- a/panther_battery/include/panther_battery/battery_driver_node.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_driver_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_DRIVER_NODE_HPP_ -#define PANTHER_BATTERY_BATTERY_DRIVER_NODE_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_DRIVER_NODE_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_DRIVER_NODE_HPP_ #include #include @@ -23,11 +23,11 @@ #include "panther_msgs/msg/robot_driver_state.hpp" -#include "panther_battery/adc_data_reader.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/adc_data_reader.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" -namespace panther_battery +namespace husarion_ugv_battery { using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; @@ -60,6 +60,6 @@ class BatteryDriverNode : public rclcpp::Node std::shared_ptr diagnostic_updater_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_DRIVER_NODE_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_DRIVER_NODE_HPP_ diff --git a/panther_battery/include/panther_battery/battery_publisher/battery_publisher.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp similarity index 88% rename from panther_battery/include/panther_battery/battery_publisher/battery_publisher.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp index 688f1899c..9258b9a51 100644 --- a/panther_battery/include/panther_battery/battery_publisher/battery_publisher.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/battery_publisher.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_PUBLISHER_BATTERY_PUBLISHER_HPP_ -#define PANTHER_BATTERY_BATTERY_PUBLISHER_BATTERY_PUBLISHER_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_BATTERY_PUBLISHER_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_BATTERY_PUBLISHER_HPP_ #include @@ -25,7 +25,7 @@ #include "panther_msgs/msg/charging_status.hpp" #include "panther_msgs/msg/io_state.hpp" -namespace panther_battery +namespace husarion_ugv_battery { using BatteryStateMsg = sensor_msgs::msg::BatteryState; @@ -71,6 +71,6 @@ class BatteryPublisher rclcpp::Subscription::SharedPtr io_state_sub_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_PUBLISHER_BATTERY_PUBLISHER_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_BATTERY_PUBLISHER_HPP_ diff --git a/panther_battery/include/panther_battery/battery_publisher/dual_battery_publisher.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/dual_battery_publisher.hpp similarity index 84% rename from panther_battery/include/panther_battery/battery_publisher/dual_battery_publisher.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/dual_battery_publisher.hpp index 9890465fb..738d7766e 100644 --- a/panther_battery/include/panther_battery/battery_publisher/dual_battery_publisher.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/dual_battery_publisher.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_PUBLISHER_DUAL_BATTERY_PUBLISHER_HPP_ -#define PANTHER_BATTERY_BATTERY_PUBLISHER_DUAL_BATTERY_PUBLISHER_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_DUAL_BATTERY_PUBLISHER_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_DUAL_BATTERY_PUBLISHER_HPP_ #include #include #include "rclcpp/rclcpp.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" -namespace panther_battery +namespace husarion_ugv_battery { class DualBatteryPublisher : public BatteryPublisher @@ -66,6 +66,6 @@ class DualBatteryPublisher : public BatteryPublisher rclcpp::Publisher::SharedPtr charging_status_pub_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_PUBLISHER_DUAL_BATTERY_PUBLISHER_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_DUAL_BATTERY_PUBLISHER_HPP_ diff --git a/panther_battery/include/panther_battery/battery_publisher/single_battery_publisher.hpp b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/single_battery_publisher.hpp similarity index 78% rename from panther_battery/include/panther_battery/battery_publisher/single_battery_publisher.hpp rename to husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/single_battery_publisher.hpp index 29be9bc5c..f1e65ecfe 100644 --- a/panther_battery/include/panther_battery/battery_publisher/single_battery_publisher.hpp +++ b/husarion_ugv_battery/include/husarion_ugv_battery/battery_publisher/single_battery_publisher.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_BATTERY_PUBLISHER_SINGLE_BATTERY_PUBLISHER_HPP_ -#define PANTHER_BATTERY_BATTERY_PUBLISHER_SINGLE_BATTERY_PUBLISHER_HPP_ +#ifndef HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_SINGLE_BATTERY_PUBLISHER_HPP_ +#define HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_SINGLE_BATTERY_PUBLISHER_HPP_ #include #include "rclcpp/rclcpp.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" -namespace panther_battery +namespace husarion_ugv_battery { class SingleBatteryPublisher : public BatteryPublisher @@ -51,6 +51,6 @@ class SingleBatteryPublisher : public BatteryPublisher rclcpp::Publisher::SharedPtr charging_status_pub_; }; -} // namespace panther_battery +} // namespace husarion_ugv_battery -#endif // PANTHER_BATTERY_BATTERY_PUBLISHER_SINGLE_BATTERY_PUBLISHER_HPP_ +#endif // HUSARION_UGV_BATTERY_BATTERY_PUBLISHER_SINGLE_BATTERY_PUBLISHER_HPP_ diff --git a/panther_battery/launch/battery.launch.py b/husarion_ugv_battery/launch/battery.launch.py similarity index 97% rename from panther_battery/launch/battery.launch.py rename to husarion_ugv_battery/launch/battery.launch.py index 51139e50e..d8327e332 100644 --- a/panther_battery/launch/battery.launch.py +++ b/husarion_ugv_battery/launch/battery.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): ) battery_driver_node = Node( - package="panther_battery", + package="husarion_ugv_battery", executable="battery_driver_node", name="battery_driver", namespace=namespace, diff --git a/panther_battery/package.xml b/husarion_ugv_battery/package.xml similarity index 93% rename from panther_battery/package.xml rename to husarion_ugv_battery/package.xml index 8e67a1b9b..70f025d7e 100644 --- a/panther_battery/package.xml +++ b/husarion_ugv_battery/package.xml @@ -1,7 +1,7 @@ - panther_battery + husarion_ugv_battery 2.1.1 Nodes monitoring the battery state of Husarion Panhter robot Husarion @@ -17,8 +17,8 @@ ament_cmake diagnostic_updater + husarion_ugv_utils panther_msgs - panther_utils rclcpp sensor_msgs diff --git a/panther_battery/src/battery/adc_battery.cpp b/husarion_ugv_battery/src/battery/adc_battery.cpp similarity index 93% rename from panther_battery/src/battery/adc_battery.cpp rename to husarion_ugv_battery/src/battery/adc_battery.cpp index 968f48236..cd13f25a0 100644 --- a/panther_battery/src/battery/adc_battery.cpp +++ b/husarion_ugv_battery/src/battery/adc_battery.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_battery/battery/adc_battery.hpp" +#include "husarion_ugv_battery/battery/adc_battery.hpp" #include #include @@ -24,9 +24,9 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_utils/moving_average.hpp" +#include "husarion_ugv_utils/moving_average.hpp" -namespace panther_battery +namespace husarion_ugv_battery { ADCBattery::ADCBattery( @@ -35,13 +35,13 @@ ADCBattery::ADCBattery( const ADCBatteryParams & params) : ReadVoltage(read_voltage), ReadCurrent(read_current), ReadTemp(read_temp), ReadCharge(read_charge) { - voltage_ma_ = std::make_unique>( + voltage_ma_ = std::make_unique>( params.voltage_window_len, std::numeric_limits::quiet_NaN()); - current_ma_ = std::make_unique>( + current_ma_ = std::make_unique>( params.current_window_len, std::numeric_limits::quiet_NaN()); - temp_ma_ = std::make_unique>( + temp_ma_ = std::make_unique>( params.temp_window_len, std::numeric_limits::quiet_NaN()); - charge_ma_ = std::make_unique>( + charge_ma_ = std::make_unique>( params.charge_window_len, std::numeric_limits::quiet_NaN()); } @@ -197,4 +197,4 @@ std::uint8_t ADCBattery::GetBatteryHealth(const float voltage, const float temp) } } -} // namespace panther_battery +} // namespace husarion_ugv_battery diff --git a/panther_battery/src/battery/roboteq_battery.cpp b/husarion_ugv_battery/src/battery/roboteq_battery.cpp similarity index 94% rename from panther_battery/src/battery/roboteq_battery.cpp rename to husarion_ugv_battery/src/battery/roboteq_battery.cpp index 6cd0f3fde..7d2d870d4 100644 --- a/panther_battery/src/battery/roboteq_battery.cpp +++ b/husarion_ugv_battery/src/battery/roboteq_battery.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_battery/battery/roboteq_battery.hpp" +#include "husarion_ugv_battery/battery/roboteq_battery.hpp" #include #include @@ -23,9 +23,9 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_utils/moving_average.hpp" +#include "husarion_ugv_utils/moving_average.hpp" -namespace panther_battery +namespace husarion_ugv_battery { RoboteqBattery::RoboteqBattery( @@ -33,9 +33,9 @@ RoboteqBattery::RoboteqBattery( const RoboteqBatteryParams & params) : GetRobotDriverState(get_driver_state), driver_state_timeout_(params.driver_state_timeout) { - voltage_ma_ = std::make_unique>( + voltage_ma_ = std::make_unique>( params.voltage_window_len, std::numeric_limits::quiet_NaN()); - current_ma_ = std::make_unique>( + current_ma_ = std::make_unique>( params.current_window_len, std::numeric_limits::quiet_NaN()); } @@ -157,4 +157,4 @@ bool RoboteqBattery::DriverStateHeartbeatTimeout() [](const DriverStateNamedMsg & driver) { return driver.state.heartbeat_timeout; }); } -} // namespace panther_battery +} // namespace husarion_ugv_battery diff --git a/panther_battery/src/battery_driver_node.cpp b/husarion_ugv_battery/src/battery_driver_node.cpp similarity index 91% rename from panther_battery/src/battery_driver_node.cpp rename to husarion_ugv_battery/src/battery_driver_node.cpp index f3603b87a..9ec166652 100644 --- a/panther_battery/src/battery_driver_node.cpp +++ b/husarion_ugv_battery/src/battery_driver_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_battery/battery_driver_node.hpp" +#include "husarion_ugv_battery/battery_driver_node.hpp" #include #include @@ -24,15 +24,15 @@ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" -#include "panther_battery/adc_data_reader.hpp" -#include "panther_battery/battery/adc_battery.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery/roboteq_battery.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" -#include "panther_battery/battery_publisher/dual_battery_publisher.hpp" -#include "panther_battery/battery_publisher/single_battery_publisher.hpp" +#include "husarion_ugv_battery/adc_data_reader.hpp" +#include "husarion_ugv_battery/battery/adc_battery.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery/roboteq_battery.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/battery_publisher/dual_battery_publisher.hpp" +#include "husarion_ugv_battery/battery_publisher/single_battery_publisher.hpp" -namespace panther_battery +namespace husarion_ugv_battery { BatteryDriverNode::BatteryDriverNode( @@ -157,4 +157,4 @@ void BatteryDriverNode::BatteryPubTimerCB() battery_publisher_->Publish(); } -} // namespace panther_battery +} // namespace husarion_ugv_battery diff --git a/panther_battery/src/battery_publisher/battery_publisher.cpp b/husarion_ugv_battery/src/battery_publisher/battery_publisher.cpp similarity index 96% rename from panther_battery/src/battery_publisher/battery_publisher.cpp rename to husarion_ugv_battery/src/battery_publisher/battery_publisher.cpp index e3ccb14b8..e37fcbfe4 100644 --- a/panther_battery/src/battery_publisher/battery_publisher.cpp +++ b/husarion_ugv_battery/src/battery_publisher/battery_publisher.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" #include #include @@ -21,7 +21,7 @@ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" -namespace panther_battery +namespace husarion_ugv_battery { BatteryPublisher::BatteryPublisher( @@ -140,4 +140,4 @@ rclcpp::Clock::SharedPtr BatteryPublisher::GetClock() return std::make_shared(RCL_ROS_TIME); } -} // namespace panther_battery +} // namespace husarion_ugv_battery diff --git a/panther_battery/src/battery_publisher/dual_battery_publisher.cpp b/husarion_ugv_battery/src/battery_publisher/dual_battery_publisher.cpp similarity index 96% rename from panther_battery/src/battery_publisher/dual_battery_publisher.cpp rename to husarion_ugv_battery/src/battery_publisher/dual_battery_publisher.cpp index fba8198d2..f474b1fe7 100644 --- a/panther_battery/src/battery_publisher/dual_battery_publisher.cpp +++ b/husarion_ugv_battery/src/battery_publisher/dual_battery_publisher.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_battery/battery_publisher/dual_battery_publisher.hpp" +#include "husarion_ugv_battery/battery_publisher/dual_battery_publisher.hpp" #include #include @@ -24,11 +24,11 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" -#include "panther_utils/ros_utils.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_utils/ros_utils.hpp" -namespace panther_battery +namespace husarion_ugv_battery { DualBatteryPublisher::DualBatteryPublisher( @@ -172,10 +172,10 @@ ChargingStatusMsg DualBatteryPublisher::MergeChargingStatusMsgs( ChargingStatusMsg charging_status_msg; try { - panther_utils::ros::VerifyTimestampGap( + husarion_ugv_utils::ros::VerifyTimestampGap( charging_status_msg_1.header, charging_status_msg_2.header, std::chrono::seconds(1)); - charging_status_msg.header = panther_utils::ros::MergeHeaders( + charging_status_msg.header = husarion_ugv_utils::ros::MergeHeaders( charging_status_msg_1.header, charging_status_msg_2.header); } catch (const std::exception & e) { RCLCPP_ERROR_STREAM_THROTTLE( @@ -251,4 +251,4 @@ void DualBatteryPublisher::DiagnoseStatus(diagnostic_updater::DiagnosticStatusWr status.summary(diagnostic_updater::DiagnosticStatusWrapper::OK, "Battery status monitoring"); } -} // namespace panther_battery +} // namespace husarion_ugv_battery diff --git a/panther_battery/src/battery_publisher/single_battery_publisher.cpp b/husarion_ugv_battery/src/battery_publisher/single_battery_publisher.cpp similarity index 92% rename from panther_battery/src/battery_publisher/single_battery_publisher.cpp rename to husarion_ugv_battery/src/battery_publisher/single_battery_publisher.cpp index 4916e647c..92e4d0031 100644 --- a/panther_battery/src/battery_publisher/single_battery_publisher.cpp +++ b/husarion_ugv_battery/src/battery_publisher/single_battery_publisher.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_battery/battery_publisher/single_battery_publisher.hpp" +#include "husarion_ugv_battery/battery_publisher/single_battery_publisher.hpp" #include #include @@ -23,10 +23,10 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" -namespace panther_battery +namespace husarion_ugv_battery { SingleBatteryPublisher::SingleBatteryPublisher( @@ -106,4 +106,4 @@ void SingleBatteryPublisher::DiagnoseStatus(diagnostic_updater::DiagnosticStatus status.summary(diagnostic_updater::DiagnosticStatusWrapper::OK, "Battery status monitoring"); } -} // namespace panther_battery +} // namespace husarion_ugv_battery diff --git a/panther_battery/src/main.cpp b/husarion_ugv_battery/src/main.cpp similarity index 86% rename from panther_battery/src/main.cpp rename to husarion_ugv_battery/src/main.cpp index b759fd33a..9dc84ddfd 100644 --- a/panther_battery/src/main.cpp +++ b/husarion_ugv_battery/src/main.cpp @@ -18,13 +18,14 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_battery/battery_driver_node.hpp" +#include "husarion_ugv_battery/battery_driver_node.hpp" int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto battery_driver_node = std::make_shared("battery_driver"); + auto battery_driver_node = + std::make_shared("battery_driver"); try { rclcpp::spin(battery_driver_node); diff --git a/panther_battery/test/battery/test_adc_battery.cpp b/husarion_ugv_battery/test/battery/test_adc_battery.cpp similarity index 93% rename from panther_battery/test/battery/test_adc_battery.cpp rename to husarion_ugv_battery/test/battery/test_adc_battery.cpp index 986f7cdb1..9486c85ef 100644 --- a/panther_battery/test/battery/test_adc_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_adc_battery.cpp @@ -24,8 +24,8 @@ #include "panther_msgs/msg/charging_status.hpp" -#include "panther_battery/battery/adc_battery.hpp" -#include "panther_utils/test/test_utils.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; @@ -54,7 +54,7 @@ class TestADCBattery : public testing::Test float battery_temp_raw_; float battery_charge_raw_; - std::unique_ptr battery_; + std::unique_ptr battery_; BatteryStateMsg battery_state_; ChargingStatusMsg charging_status_; @@ -62,8 +62,8 @@ class TestADCBattery : public testing::Test TestADCBattery::TestADCBattery() { - panther_battery::ADCBatteryParams params = {10, 10, 10, 10}; - battery_ = std::make_unique( + husarion_ugv_battery::ADCBatteryParams params = {10, 10, 10, 10}; + battery_ = std::make_unique( [&]() { return battery_voltage_raw_; }, [&]() { return battery_current_raw_; }, [&]() { return battery_temp_raw_; }, [&]() { return battery_charge_raw_; }, params); } @@ -92,8 +92,9 @@ void TestADCBattery::TestDefaultBatteryStateMsg( EXPECT_TRUE(std::isnan(battery_state_.capacity)); EXPECT_FLOAT_EQ(20.0, battery_state_.design_capacity); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_TECHNOLOGY_LION, battery_state_.power_supply_technology); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); + EXPECT_TRUE( + husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); EXPECT_TRUE(battery_state_.present); EXPECT_EQ("user_compartment", battery_state_.location); @@ -116,8 +117,9 @@ void TestADCBattery::TestBatteryStateMsg( EXPECT_TRUE(std::isnan(battery_state_.capacity)); EXPECT_FLOAT_EQ(20.0, battery_state_.design_capacity); EXPECT_FLOAT_EQ(expected_temp, battery_state_.temperature); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); + EXPECT_TRUE( + husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_TECHNOLOGY_LION, battery_state_.power_supply_technology); EXPECT_EQ("user_compartment", battery_state_.location); diff --git a/panther_battery/test/battery/test_battery.cpp b/husarion_ugv_battery/test/battery/test_battery.cpp similarity index 93% rename from panther_battery/test/battery/test_battery.cpp rename to husarion_ugv_battery/test/battery/test_battery.cpp index cdbdf3812..9b2d12c0d 100644 --- a/panther_battery/test/battery/test_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_battery.cpp @@ -24,13 +24,13 @@ #include "panther_msgs/msg/charging_status.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_utils/test/test_utils.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; -class BatteryWrapper : public panther_battery::Battery +class BatteryWrapper : public husarion_ugv_battery::Battery { public: BatteryWrapper() {} @@ -80,8 +80,9 @@ void TestBattery::TestDefaultBatteryStateMsg( EXPECT_TRUE(std::isnan(battery_state_.capacity)); EXPECT_FLOAT_EQ(20.0, battery_state_.design_capacity); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_TECHNOLOGY_LION, battery_state_.power_supply_technology); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); + EXPECT_TRUE( + husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); EXPECT_TRUE(battery_state_.present); EXPECT_EQ("user_compartment", battery_state_.location); diff --git a/panther_battery/test/battery/test_roboteq_battery.cpp b/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp similarity index 92% rename from panther_battery/test/battery/test_roboteq_battery.cpp rename to husarion_ugv_battery/test/battery/test_roboteq_battery.cpp index 8ca850f1f..26674df87 100644 --- a/panther_battery/test/battery/test_roboteq_battery.cpp +++ b/husarion_ugv_battery/test/battery/test_roboteq_battery.cpp @@ -27,18 +27,18 @@ #include "panther_msgs/msg/driver_state_named.hpp" #include "panther_msgs/msg/robot_driver_state.hpp" -#include "panther_battery/battery/roboteq_battery.hpp" -#include "panther_utils/test/test_utils.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; -class RoboteqBatteryWrapper : public panther_battery::RoboteqBattery +class RoboteqBatteryWrapper : public husarion_ugv_battery::RoboteqBattery { public: RoboteqBatteryWrapper( const std::function & get_driver_state, - const panther_battery::RoboteqBatteryParams & params) + const husarion_ugv_battery::RoboteqBatteryParams & params) : RoboteqBattery(get_driver_state, params) { } @@ -73,7 +73,7 @@ class TestRoboteqBattery : public testing::Test TestRoboteqBattery::TestRoboteqBattery() { - const panther_battery::RoboteqBatteryParams params = {kRobotDriverStateTimeout, 10, 10}; + const husarion_ugv_battery::RoboteqBatteryParams params = {kRobotDriverStateTimeout, 10, 10}; battery_ = std::make_unique([&]() { return driver_state_; }, params); } @@ -105,8 +105,8 @@ void TestRoboteqBattery::TestDefaultBatteryStateMsg( EXPECT_TRUE(std::isnan(battery_state_.capacity)); EXPECT_FLOAT_EQ(20.0, battery_state_.design_capacity); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_TECHNOLOGY_LION, battery_state_.power_supply_technology); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); EXPECT_TRUE(battery_state_.present); EXPECT_EQ("user_compartment", battery_state_.location); @@ -128,8 +128,8 @@ void TestRoboteqBattery::TestBatteryStateMsg( EXPECT_TRUE(std::isnan(battery_state_.capacity)); EXPECT_TRUE(std::isnan(battery_state_.temperature)); EXPECT_FLOAT_EQ(20.0, battery_state_.design_capacity); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); - EXPECT_TRUE(panther_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_voltage)); + EXPECT_TRUE(husarion_ugv_utils::test_utils::CheckNaNVector(battery_state_.cell_temperature)); EXPECT_EQ(BatteryStateMsg::POWER_SUPPLY_TECHNOLOGY_LION, battery_state_.power_supply_technology); EXPECT_EQ("user_compartment", battery_state_.location); diff --git a/panther_battery/test/battery_publisher/test_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp similarity index 94% rename from panther_battery/test/battery_publisher/test_battery_publisher.cpp rename to husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp index 4ed567b16..f5924c731 100644 --- a/panther_battery/test/battery_publisher/test_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_battery_publisher.cpp @@ -24,18 +24,18 @@ #include "panther_msgs/msg/io_state.hpp" -#include "panther_battery/battery_publisher/battery_publisher.hpp" +#include "husarion_ugv_battery/battery_publisher/battery_publisher.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; using IOStateMsg = panther_msgs::msg::IOState; -class BatteryPublisherWrapper : public panther_battery::BatteryPublisher +class BatteryPublisherWrapper : public husarion_ugv_battery::BatteryPublisher { public: BatteryPublisherWrapper( const rclcpp::Node::SharedPtr & node, std::shared_ptr diagnostic_updater) - : panther_battery::BatteryPublisher(node, diagnostic_updater) + : husarion_ugv_battery::BatteryPublisher(node, diagnostic_updater) { } diff --git a/panther_battery/test/battery_publisher/test_dual_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp similarity index 93% rename from panther_battery/test/battery_publisher/test_dual_battery_publisher.cpp rename to husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp index 0740b7fa9..74bcb3581 100644 --- a/panther_battery/test/battery_publisher/test_dual_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_dual_battery_publisher.cpp @@ -24,22 +24,22 @@ #include "panther_msgs/msg/charging_status.hpp" -#include "panther_battery/battery/adc_battery.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/dual_battery_publisher.hpp" -#include "panther_utils/test/ros_test_utils.hpp" +#include "husarion_ugv_battery/battery/adc_battery.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/dual_battery_publisher.hpp" +#include "husarion_ugv_utils/test/ros_test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; using ChargingStatusMsg = panther_msgs::msg::ChargingStatus; -class DualBatteryPublisherWrapper : public panther_battery::DualBatteryPublisher +class DualBatteryPublisherWrapper : public husarion_ugv_battery::DualBatteryPublisher { public: DualBatteryPublisherWrapper( const rclcpp::Node::SharedPtr & node, std::shared_ptr diagnostic_updater, - std::shared_ptr & battery_1, - std::shared_ptr & battery_2) + std::shared_ptr & battery_1, + std::shared_ptr & battery_2) : DualBatteryPublisher(node, diagnostic_updater, battery_1, battery_2) { } @@ -90,8 +90,8 @@ class TestDualBatteryPublisher : public testing::Test rclcpp::Subscription::SharedPtr battery_1_sub_; rclcpp::Subscription::SharedPtr battery_2_sub_; - std::shared_ptr battery_1_; - std::shared_ptr battery_2_; + std::shared_ptr battery_1_; + std::shared_ptr battery_2_; std::shared_ptr battery_publisher_; BatteryStateMsg::SharedPtr battery_state_; BatteryStateMsg::SharedPtr battery_1_state_; @@ -100,11 +100,11 @@ class TestDualBatteryPublisher : public testing::Test TestDualBatteryPublisher::TestDualBatteryPublisher() { - panther_battery::ADCBatteryParams params = {10, 10, 10, 10}; - battery_1_ = std::make_shared( + husarion_ugv_battery::ADCBatteryParams params = {10, 10, 10, 10}; + battery_1_ = std::make_shared( [&]() { return 1.6; }, [&]() { return 0.02; }, [&]() { return 1.6; }, [&]() { return 0.4; }, params); - battery_2_ = std::make_shared( + battery_2_ = std::make_shared( [&]() { return 1.6; }, [&]() { return 0.02; }, [&]() { return 1.6; }, [&]() { return 0.4; }, params); @@ -139,13 +139,13 @@ void TestDualBatteryPublisher::TestMergeBatteryPowerSupplyStatus( TEST_F(TestDualBatteryPublisher, CorrectTopicPublished) { battery_publisher_->Publish(); - ASSERT_TRUE( - panther_utils::test_utils::WaitForMsg(node_, battery_state_, std::chrono::milliseconds(1000))); + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( + node_, battery_state_, std::chrono::milliseconds(1000))); battery_publisher_->Publish(); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( node_, battery_1_state_, std::chrono::milliseconds(1000))); battery_publisher_->Publish(); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( node_, battery_2_state_, std::chrono::milliseconds(1000))); } diff --git a/panther_battery/test/battery_publisher/test_single_battery_publisher.cpp b/husarion_ugv_battery/test/battery_publisher/test_single_battery_publisher.cpp similarity index 75% rename from panther_battery/test/battery_publisher/test_single_battery_publisher.cpp rename to husarion_ugv_battery/test/battery_publisher/test_single_battery_publisher.cpp index f7a04c3fa..3d98a9a74 100644 --- a/panther_battery/test/battery_publisher/test_single_battery_publisher.cpp +++ b/husarion_ugv_battery/test/battery_publisher/test_single_battery_publisher.cpp @@ -21,10 +21,10 @@ #include "sensor_msgs/msg/battery_state.hpp" -#include "panther_battery/battery/adc_battery.hpp" -#include "panther_battery/battery/battery.hpp" -#include "panther_battery/battery_publisher/single_battery_publisher.hpp" -#include "panther_utils/test/ros_test_utils.hpp" +#include "husarion_ugv_battery/battery/adc_battery.hpp" +#include "husarion_ugv_battery/battery/battery.hpp" +#include "husarion_ugv_battery/battery_publisher/single_battery_publisher.hpp" +#include "husarion_ugv_utils/test/ros_test_utils.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; @@ -40,16 +40,16 @@ class TestSingleBatteryPublisher : public testing::Test rclcpp::Subscription::SharedPtr battery_sub_; rclcpp::Subscription::SharedPtr battery_1_sub_; - std::shared_ptr battery_; - std::shared_ptr battery_publisher_; + std::shared_ptr battery_; + std::shared_ptr battery_publisher_; BatteryStateMsg::SharedPtr battery_state_; BatteryStateMsg::SharedPtr battery_1_state_; }; TestSingleBatteryPublisher::TestSingleBatteryPublisher() { - panther_battery::ADCBatteryParams params = {10, 10, 10, 10}; - battery_ = std::make_shared( + husarion_ugv_battery::ADCBatteryParams params = {10, 10, 10, 10}; + battery_ = std::make_shared( [&]() { return 1.6; }, [&]() { return 0.02; }, [&]() { return 1.6; }, [&]() { return 0.4; }, params); @@ -61,17 +61,17 @@ TestSingleBatteryPublisher::TestSingleBatteryPublisher() battery_1_sub_ = node_->create_subscription( "/_battery/battery_1_status_raw", 10, [&](const BatteryStateMsg::SharedPtr msg) { battery_1_state_ = msg; }); - battery_publisher_ = std::make_shared( + battery_publisher_ = std::make_shared( node_, diagnostic_updater_, battery_); } TEST_F(TestSingleBatteryPublisher, CorrectTopicPublished) { battery_publisher_->Publish(); - ASSERT_TRUE( - panther_utils::test_utils::WaitForMsg(node_, battery_state_, std::chrono::milliseconds(1000))); + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( + node_, battery_state_, std::chrono::milliseconds(1000))); battery_publisher_->Publish(); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( node_, battery_1_state_, std::chrono::milliseconds(1000))); } diff --git a/panther_battery/test/test_adc_data_reader.cpp b/husarion_ugv_battery/test/test_adc_data_reader.cpp similarity index 92% rename from panther_battery/test/test_adc_data_reader.cpp rename to husarion_ugv_battery/test/test_adc_data_reader.cpp index c9fd3d943..bbb322bc8 100644 --- a/panther_battery/test/test_adc_data_reader.cpp +++ b/husarion_ugv_battery/test/test_adc_data_reader.cpp @@ -18,7 +18,7 @@ #include "gtest/gtest.h" -#include "panther_battery/adc_data_reader.hpp" +#include "husarion_ugv_battery/adc_data_reader.hpp" class TestADCDataReader : public testing::Test { @@ -27,7 +27,7 @@ class TestADCDataReader : public testing::Test ~TestADCDataReader(); protected: - std::shared_ptr data_reader_; + std::shared_ptr data_reader_; std::filesystem::path data_file_path_; std::filesystem::path scale_file_path_; std::ofstream file_; @@ -44,7 +44,7 @@ TestADCDataReader::TestADCDataReader() WriteNumberToFile(1.0, scale_file_path_); - data_reader_ = std::make_shared(current_path); + data_reader_ = std::make_shared(current_path); } TestADCDataReader::~TestADCDataReader() diff --git a/panther_battery/test/test_battery_driver_node_adc_dual.cpp b/husarion_ugv_battery/test/test_battery_driver_node_adc_dual.cpp similarity index 91% rename from panther_battery/test/test_battery_driver_node_adc_dual.cpp rename to husarion_ugv_battery/test/test_battery_driver_node_adc_dual.cpp index 740ba838d..2718407a7 100644 --- a/panther_battery/test/test_battery_driver_node_adc_dual.cpp +++ b/husarion_ugv_battery/test/test_battery_driver_node_adc_dual.cpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_utils/test/ros_test_utils.hpp" +#include "husarion_ugv_utils/test/ros_test_utils.hpp" class TestBatteryNodeADCDual : public TestBatteryNode { @@ -30,7 +30,7 @@ class TestBatteryNodeADCDual : public TestBatteryNode TEST_F(TestBatteryNodeADCDual, BatteryValues) { - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // This is done to check if channels of ADC readers were assigned correctly, not to verify @@ -51,7 +51,7 @@ TEST_F(TestBatteryNodeADCDual, BatteryValues) // Change value of battery 2 reading one by one and check if corresponding values in battery 1 // stops matching WriteNumberToFile(1600, std::filesystem::path(device1_path_ / "in_voltage3_raw")); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_2_state_, std::chrono::milliseconds(1000))); EXPECT_FALSE( fabs(battery_1_state_->voltage - battery_2_state_->voltage) < @@ -67,7 +67,7 @@ TEST_F(TestBatteryNodeADCDual, BatteryValues) WriteNumberToFile(900, std::filesystem::path(device1_path_ / "in_voltage1_raw")); WriteNumberToFile(100, std::filesystem::path(device0_path_ / "in_voltage2_raw")); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_2_state_, std::chrono::milliseconds(1000))); EXPECT_FALSE( fabs(battery_1_state_->current - battery_2_state_->current) < @@ -75,7 +75,7 @@ TEST_F(TestBatteryNodeADCDual, BatteryValues) EXPECT_FLOAT_EQ(battery_1_state_->temperature, battery_2_state_->temperature); WriteNumberToFile(1000, std::filesystem::path(device0_path_ / "in_voltage0_raw")); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_2_state_, std::chrono::milliseconds(1000))); EXPECT_FALSE( fabs(battery_1_state_->temperature - battery_2_state_->temperature) < @@ -84,7 +84,7 @@ TEST_F(TestBatteryNodeADCDual, BatteryValues) TEST_F(TestBatteryNodeADCDual, BatteryTimeout) { - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Battery state msg should have some values @@ -98,7 +98,7 @@ TEST_F(TestBatteryNodeADCDual, BatteryTimeout) std::filesystem::remove(std::filesystem::path(device0_path_ / "in_voltage2_raw")); std::filesystem::remove(std::filesystem::path(device1_path_ / "in_voltage2_raw")); std::this_thread::sleep_for(std::chrono::milliseconds(2500)); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); // Battery state msg values should be NaN @@ -114,14 +114,14 @@ TEST_F(TestBatteryNodeADCDual, BatteryTimeout) TEST_F(TestBatteryNodeADCDual, BatteryCharging) { // Wait for node to initialize - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Publish charger connected state IOStateMsg io_state; io_state.charger_connected = true; io_state_pub_->publish(io_state); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); EXPECT_NE(battery_state_->power_supply_status, BatteryStateMsg::POWER_SUPPLY_STATUS_DISCHARGING); diff --git a/panther_battery/test/test_battery_driver_node_adc_single.cpp b/husarion_ugv_battery/test/test_battery_driver_node_adc_single.cpp similarity index 91% rename from panther_battery/test/test_battery_driver_node_adc_single.cpp rename to husarion_ugv_battery/test/test_battery_driver_node_adc_single.cpp index cc26bfe76..8c0ec4987 100644 --- a/panther_battery/test/test_battery_driver_node_adc_single.cpp +++ b/husarion_ugv_battery/test/test_battery_driver_node_adc_single.cpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_utils/test/ros_test_utils.hpp" +#include "husarion_ugv_utils/test/ros_test_utils.hpp" class TestBatteryNodeADCSingle : public TestBatteryNode { @@ -35,7 +35,7 @@ TEST_F(TestBatteryNodeADCSingle, BatteryValues) WriteNumberToFile(1600, std::filesystem::path(device1_path_ / "in_voltage3_raw")); WriteNumberToFile(100, std::filesystem::path(device0_path_ / "in_voltage2_raw")); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // This is done to check if channels of ADC readers were assigned correctly, not to verify @@ -56,7 +56,7 @@ TEST_F(TestBatteryNodeADCSingle, BatteryValues) TEST_F(TestBatteryNodeADCSingle, BatteryTimeout) { - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Battery state msg should have some values @@ -70,7 +70,7 @@ TEST_F(TestBatteryNodeADCSingle, BatteryTimeout) std::filesystem::remove(std::filesystem::path(device0_path_ / "in_voltage2_raw")); std::filesystem::remove(std::filesystem::path(device1_path_ / "in_voltage2_raw")); std::this_thread::sleep_for(std::chrono::milliseconds(2500)); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); // Battery state msg values should be NaN @@ -86,14 +86,14 @@ TEST_F(TestBatteryNodeADCSingle, BatteryTimeout) TEST_F(TestBatteryNodeADCSingle, BatteryCharging) { // Wait for node to initialize - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Publish charger connected state IOStateMsg io_state; io_state.charger_connected = true; io_state_pub_->publish(io_state); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); EXPECT_NE(battery_state_->power_supply_status, BatteryStateMsg::POWER_SUPPLY_STATUS_DISCHARGING); @@ -105,7 +105,7 @@ TEST_F(TestBatteryNodeADCSingle, RoboteqInitOnADCFail) std::filesystem::remove_all(device0_path_); // Wait for node to initialize - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Battery state status should be UNKNOWN @@ -116,7 +116,7 @@ TEST_F(TestBatteryNodeADCSingle, RoboteqInitOnADCFail) driver_state.header.stamp = battery_driver_node_->get_clock()->now(); driver_state_pub_->publish(driver_state); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); // Battery state status should be different than UNKNOWN diff --git a/panther_battery/test/test_battery_driver_node_roboteq.cpp b/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp similarity index 93% rename from panther_battery/test/test_battery_driver_node_roboteq.cpp rename to husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp index 84eb00b9c..8393b1b9f 100644 --- a/panther_battery/test/test_battery_driver_node_roboteq.cpp +++ b/husarion_ugv_battery/test/test_battery_driver_node_roboteq.cpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" -#include "panther_utils/test/ros_test_utils.hpp" +#include "husarion_ugv_utils/test/ros_test_utils.hpp" class TestBatteryNodeRoboteq : public TestBatteryNode { @@ -33,7 +33,7 @@ class TestBatteryNodeRoboteq : public TestBatteryNode TEST_F(TestBatteryNodeRoboteq, BatteryValues) { // Wait for node to initialize - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Battery state msg values should be NaN @@ -54,7 +54,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryValues) driver_state.driver_states.push_back(motor_controller); driver_state_pub_->publish(driver_state); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); // This is done to check if values were read correctly, not to verify calculations. @@ -72,7 +72,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryValues) TEST_F(TestBatteryNodeRoboteq, BatteryTimeout) { // Wait for node to initialize - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(5000))); // Battery state msg values should be NaN @@ -94,7 +94,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryTimeout) driver_state.driver_states.push_back(motor_controller); driver_state_pub_->publish(driver_state); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); // Battery state msg should have some values @@ -105,7 +105,7 @@ TEST_F(TestBatteryNodeRoboteq, BatteryTimeout) // Wait for timeout std::this_thread::sleep_for(std::chrono::milliseconds(1500)); - ASSERT_TRUE(panther_utils::test_utils::WaitForMsg( + ASSERT_TRUE(husarion_ugv_utils::test_utils::WaitForMsg( battery_driver_node_, battery_state_, std::chrono::milliseconds(1000))); // Battery state msg values should be NaN diff --git a/panther_battery/test/utils/test_battery_driver_node.hpp b/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp similarity index 93% rename from panther_battery/test/utils/test_battery_driver_node.hpp rename to husarion_ugv_battery/test/utils/test_battery_driver_node.hpp index bad9542c3..319dfd6db 100644 --- a/panther_battery/test/utils/test_battery_driver_node.hpp +++ b/husarion_ugv_battery/test/utils/test_battery_driver_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_BATTERY_UTILS_TEST_BATTERY_DRIVER_NODE_HPP_ -#define PANTHER_BATTERY_UTILS_TEST_BATTERY_DRIVER_NODE_HPP_ +#ifndef HUSARION_UGV_BATTERY_UTILS_TEST_BATTERY_DRIVER_NODE_HPP_ +#define HUSARION_UGV_BATTERY_UTILS_TEST_BATTERY_DRIVER_NODE_HPP_ #include #include @@ -31,7 +31,7 @@ #include "panther_msgs/msg/io_state.hpp" #include "panther_msgs/msg/robot_driver_state.hpp" -#include "panther_battery/battery_driver_node.hpp" +#include "husarion_ugv_battery/battery_driver_node.hpp" using BatteryStateMsg = sensor_msgs::msg::BatteryState; using RobotDriverStateMsg = panther_msgs::msg::RobotDriverState; @@ -55,7 +55,7 @@ class TestBatteryNode : public testing::Test BatteryStateMsg::SharedPtr battery_state_; BatteryStateMsg::SharedPtr battery_1_state_; BatteryStateMsg::SharedPtr battery_2_state_; - std::shared_ptr battery_driver_node_; + std::shared_ptr battery_driver_node_; rclcpp::Subscription::SharedPtr battery_sub_; rclcpp::Subscription::SharedPtr battery_1_sub_; rclcpp::Subscription::SharedPtr battery_2_sub_; @@ -103,7 +103,7 @@ TestBatteryNode::TestBatteryNode(const bool use_adc_battery, const bool dual_bat rclcpp::NodeOptions options; options.parameter_overrides(params); - battery_driver_node_ = std::make_shared( + battery_driver_node_ = std::make_shared( "battery_driver", options); battery_sub_ = battery_driver_node_->create_subscription( @@ -145,4 +145,4 @@ void TestBatteryNode::WriteNumberToFile(const T number, const std::string & file } } -#endif // PANTHER_BATTERY_UTILS_TEST_BATTERY_DRIVER_NODE_HPP_ +#endif // HUSARION_UGV_BATTERY_UTILS_TEST_BATTERY_DRIVER_NODE_HPP_ diff --git a/panther_bringup/CHANGELOG.rst b/husarion_ugv_bringup/CHANGELOG.rst similarity index 100% rename from panther_bringup/CHANGELOG.rst rename to husarion_ugv_bringup/CHANGELOG.rst diff --git a/panther_bringup/CMakeLists.txt b/husarion_ugv_bringup/CMakeLists.txt similarity index 83% rename from panther_bringup/CMakeLists.txt rename to husarion_ugv_bringup/CMakeLists.txt index 793057508..6fb4694db 100644 --- a/panther_bringup/CMakeLists.txt +++ b/husarion_ugv_bringup/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(panther_bringup) +project(husarion_ugv_bringup) find_package(ament_cmake REQUIRED) diff --git a/panther_bringup/README.md b/husarion_ugv_bringup/README.md similarity index 87% rename from panther_bringup/README.md rename to husarion_ugv_bringup/README.md index b12b4218d..caafb8c83 100644 --- a/panther_bringup/README.md +++ b/husarion_ugv_bringup/README.md @@ -1,6 +1,6 @@ -# panther_bringup +# husarion_ugv_bringup -The package contains the default configuration and launch files necessary to start all the basic functionalities of the Husarion Panther robot. +The package contains the default configuration and launch files necessary to start all the basic functionalities of the Husarion UGV robots. ## Launch Files diff --git a/panther_bringup/launch/bringup.launch.py b/husarion_ugv_bringup/launch/bringup.launch.py similarity index 84% rename from panther_bringup/launch/bringup.launch.py rename to husarion_ugv_bringup/launch/bringup.launch.py index 37886eb7c..e27d71043 100644 --- a/panther_bringup/launch/bringup.launch.py +++ b/husarion_ugv_bringup/launch/bringup.launch.py @@ -16,6 +16,7 @@ import os +from husarion_ugv_utils.messages import welcome_msg from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, TimerAction from launch.conditions import IfCondition, UnlessCondition @@ -26,7 +27,6 @@ PathJoinSubstitution, ) from launch_ros.substitutions import FindPackageShare -from panther_utils.messages import welcome_msg def generate_launch_description(): @@ -53,8 +53,9 @@ def generate_launch_description(): choices=["True", "true", "False", "false"], ) - robot_model = os.environ.get("ROBOT_MODEL", default="PTH") - robot_model = "lynx" if robot_model == "LNX" else "panther" + robot_model_dict = {"LNX": "lynx", "PTH": "panther"} + robot_model_env = os.environ.get("ROBOT_MODEL", default="PTH") + robot_model = robot_model_dict[robot_model_env] robot_serial_no = EnvironmentVariable(name="ROBOT_SERIAL_NO", default_value="----") robot_version = EnvironmentVariable(name="ROBOT_VERSION", default_value="1.0") welcome_info = welcome_msg(robot_model, robot_serial_no, robot_version) @@ -62,7 +63,7 @@ def generate_launch_description(): controller_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_controller"), "launch", "controller.launch.py"] + [FindPackageShare("husarion_ugv_controller"), "launch", "controller.launch.py"] ) ), launch_arguments={"namespace": namespace}.items(), @@ -72,7 +73,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( PathJoinSubstitution( [ - FindPackageShare("panther_diagnostics"), + FindPackageShare("husarion_ugv_diagnostics"), "launch", "system_monitor.launch.py", ] @@ -84,7 +85,7 @@ def generate_launch_description(): lights_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_lights"), "launch", "lights.launch.py"] + [FindPackageShare("husarion_ugv_lights"), "launch", "lights.launch.py"] ) ), launch_arguments={"namespace": namespace}.items(), @@ -93,7 +94,7 @@ def generate_launch_description(): battery_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_battery"), "launch", "battery.launch.py"] + [FindPackageShare("husarion_ugv_battery"), "launch", "battery.launch.py"] ), ), launch_arguments={"namespace": namespace}.items(), @@ -102,7 +103,7 @@ def generate_launch_description(): ekf_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_localization"), "launch", "localization.launch.py"] + [FindPackageShare("husarion_ugv_localization"), "launch", "localization.launch.py"] ) ), launch_arguments={"namespace": namespace}.items(), @@ -112,7 +113,7 @@ def generate_launch_description(): manager_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_manager"), "launch", "manager.launch.py"] + [FindPackageShare("husarion_ugv_manager"), "launch", "manager.launch.py"] ) ), condition=UnlessCondition(disable_manager), diff --git a/panther_bringup/package.xml b/husarion_ugv_bringup/package.xml similarity index 80% rename from panther_bringup/package.xml rename to husarion_ugv_bringup/package.xml index a5fe44b42..4639b0781 100644 --- a/panther_bringup/package.xml +++ b/husarion_ugv_bringup/package.xml @@ -1,9 +1,9 @@ - panther_bringup + husarion_ugv_bringup 2.1.1 - Default launch files and configuration used to start Husarion Panther robot + Default launch files and configuration used to start Husarion UGV robots Husarion Apache License 2.0 @@ -15,15 +15,15 @@ ament_cmake + husarion_ugv_battery + husarion_ugv_controller + husarion_ugv_diagnostics + husarion_ugv_lights + husarion_ugv_localization + husarion_ugv_manager + husarion_ugv_utils launch launch_ros - panther_battery - panther_controller - panther_diagnostics - panther_lights - panther_localization - panther_manager - panther_utils ament_cmake diff --git a/panther_controller/CHANGELOG.rst b/husarion_ugv_controller/CHANGELOG.rst similarity index 100% rename from panther_controller/CHANGELOG.rst rename to husarion_ugv_controller/CHANGELOG.rst diff --git a/panther_localization/CMakeLists.txt b/husarion_ugv_controller/CMakeLists.txt similarity index 82% rename from panther_localization/CMakeLists.txt rename to husarion_ugv_controller/CMakeLists.txt index 33da28a6f..9cf8423aa 100644 --- a/panther_localization/CMakeLists.txt +++ b/husarion_ugv_controller/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(panther_localization) +project(husarion_ugv_controller) find_package(ament_cmake REQUIRED) diff --git a/husarion_ugv_controller/CONFIGURATION.md b/husarion_ugv_controller/CONFIGURATION.md new file mode 100644 index 000000000..01a40d15c --- /dev/null +++ b/husarion_ugv_controller/CONFIGURATION.md @@ -0,0 +1,9 @@ +# husarion_ugv_controller + +## Changing Velocity Smoothing Parameters + +The default drive controller is based on [diff_drive_controller](https://control.ros.org/master/doc/ros2_controllers/diff_drive_controller/doc/userdoc.html) from [ros2 control](https://control.ros.org/master/index.html) or [mecanum_drive_controller](https://github.com/husarion/husarion_controllers/tree/main/mecanum_drive_controller). This controller can be customized, among others: by modifying the robot's dynamic parameters (e.g. smooth the speed or limit the robot's speed and acceleration). Its parameters can be found in the [husarion_ugv_controller](https://github.com/husarion/panther_ros/tree/ros2-devel/husarion_ugv_controller/config). By default, these values correspond to the upper limits of the robot's velocities and accelerations. + +## Changing Wheel Type + +Changing wheel types is possible and can be done for both the real robot and the simulation. By default, three types of wheels are supported using the launch argument `wheel_type`. If you want to use custom wheels, all you need to do is point to the new wheel and controller configuration files using the `wheel_config_path` and `controller_config_path` parameters. These files should be based on the default files, i.e. [WH01_controller.yaml](./config/WH01_controller.yaml) and [WH01.yaml](../panther_description/config/WH01.yaml). diff --git a/panther_controller/README.md b/husarion_ugv_controller/README.md similarity index 95% rename from panther_controller/README.md rename to husarion_ugv_controller/README.md index ac600dc72..f2deb0652 100644 --- a/panther_controller/README.md +++ b/husarion_ugv_controller/README.md @@ -1,6 +1,6 @@ -# panther_controller +# husarion_ugv_controller -The package contains the default configuration and launch files necessary to start all the basic functionalities of the Husarion Panther robot. +The package contains the default configuration and launch files necessary to start all the basic functionalities of the Husarion UGV robots. ## Launch Files diff --git a/panther_controller/config/WH01_controller.yaml b/husarion_ugv_controller/config/WH01_controller.yaml similarity index 100% rename from panther_controller/config/WH01_controller.yaml rename to husarion_ugv_controller/config/WH01_controller.yaml diff --git a/panther_controller/config/WH02_controller.yaml b/husarion_ugv_controller/config/WH02_controller.yaml similarity index 100% rename from panther_controller/config/WH02_controller.yaml rename to husarion_ugv_controller/config/WH02_controller.yaml diff --git a/panther_controller/config/WH04_controller.yaml b/husarion_ugv_controller/config/WH04_controller.yaml similarity index 98% rename from panther_controller/config/WH04_controller.yaml rename to husarion_ugv_controller/config/WH04_controller.yaml index 259873503..b13bbd11e 100644 --- a/panther_controller/config/WH04_controller.yaml +++ b/husarion_ugv_controller/config/WH04_controller.yaml @@ -32,7 +32,7 @@ wheel_separation: 0.616 wheel_radius: 0.1016 - # todo: check it for panther + # TODO: check it # For skid drive kinematics it will act as ICR coefficient, kinematic model with ICR # coefficient isn't totally accurate and this coefficient can differ for various ground types wheel_separation_multiplier: 1.0 diff --git a/panther_controller/config/WH05_controller.yaml b/husarion_ugv_controller/config/WH05_controller.yaml similarity index 100% rename from panther_controller/config/WH05_controller.yaml rename to husarion_ugv_controller/config/WH05_controller.yaml diff --git a/panther_controller/launch/controller.launch.py b/husarion_ugv_controller/launch/controller.launch.py similarity index 96% rename from panther_controller/launch/controller.launch.py rename to husarion_ugv_controller/launch/controller.launch.py index 9dc30b096..2e61a3702 100644 --- a/panther_controller/launch/controller.launch.py +++ b/husarion_ugv_controller/launch/controller.launch.py @@ -52,8 +52,8 @@ def generate_launch_description(): ), description=( "Additional components configuration file. Components described in this file " - "are dynamically included in Panther's urdf." - "Panther options are described here " + "are dynamically included in robot's URDF." + "Available options are described in the manual: " "https://husarion.com/manuals/panther/panther-options/" ), ) @@ -64,14 +64,14 @@ def generate_launch_description(): "controller_config_path", default_value=PathJoinSubstitution( [ - FindPackageShare("panther_controller"), + FindPackageShare("husarion_ugv_controller"), "config", PythonExpression(["'", wheel_type, "_controller.yaml'"]), ] ), description=( "Path to controller configuration file. By default, it is located in" - " 'panther_controller/config/{wheel_type}_controller.yaml'. You can also specify" + " 'husarion_ugv_controller/config/{wheel_type}_controller.yaml'. You can also specify" " the path to your custom controller configuration file here. " ), ) @@ -286,8 +286,8 @@ def generate_launch_description(): actions = [ declare_battery_config_path_arg, - declare_robot_model_arg, # robot_model must be before wheel_type - declare_wheel_type_arg, # wheel_type must be before controller_config_path + declare_robot_model_arg, # robot_model is used by wheel_type + declare_wheel_type_arg, # wheel_type is used by controller_config_path declare_components_config_path_arg, declare_controller_config_path_arg, declare_namespace_arg, diff --git a/panther_controller/package.xml b/husarion_ugv_controller/package.xml similarity index 88% rename from panther_controller/package.xml rename to husarion_ugv_controller/package.xml index 6dea3a07d..ec8101f41 100644 --- a/panther_controller/package.xml +++ b/husarion_ugv_controller/package.xml @@ -1,9 +1,9 @@ - panther_controller + husarion_ugv_controller 2.1.1 - ros2 controllers configuration for Panther + ros2 controllers configuration for Husarion UGV robots Husarion Apache License 2.0 @@ -18,6 +18,7 @@ controller_manager diff_drive_controller + husarion_ugv_hardware_interfaces imu_sensor_broadcaster joint_state_broadcaster launch @@ -25,7 +26,6 @@ lynx_description mecanum_drive_controller panther_description - panther_hardware_interfaces robot_state_publisher xacro diff --git a/panther_diagnostics/CHANGELOG.rst b/husarion_ugv_diagnostics/CHANGELOG.rst similarity index 100% rename from panther_diagnostics/CHANGELOG.rst rename to husarion_ugv_diagnostics/CHANGELOG.rst diff --git a/panther_diagnostics/CMakeLists.txt b/husarion_ugv_diagnostics/CMakeLists.txt similarity index 97% rename from panther_diagnostics/CMakeLists.txt rename to husarion_ugv_diagnostics/CMakeLists.txt index 8794efbed..64b9751d5 100644 --- a/panther_diagnostics/CMakeLists.txt +++ b/husarion_ugv_diagnostics/CMakeLists.txt @@ -8,7 +8,7 @@ if(USE_SUPERBUILD) include(cmake/SuperBuild.cmake) return() else() - project(panther_diagnostics) + project(husarion_ugv_diagnostics) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -21,7 +21,7 @@ set(PACKAGE_DEPENDENCIES diagnostic_updater generate_parameter_library panther_msgs - panther_utils + husarion_ugv_utils PkgConfig rclcpp std_msgs) diff --git a/panther_diagnostics/README.md b/husarion_ugv_diagnostics/README.md similarity index 95% rename from panther_diagnostics/README.md rename to husarion_ugv_diagnostics/README.md index d3e213bbd..542a05ad7 100644 --- a/panther_diagnostics/README.md +++ b/husarion_ugv_diagnostics/README.md @@ -1,6 +1,6 @@ -# panther_diagnostics +# husarion_ugv_diagnostics -Package containing nodes monitoring and publishing the Built-in Computer status of Husarion Panther robot. +Package containing nodes monitoring and publishing the Built-in Computer status of Husarion UGV robots. ## Launch Files diff --git a/panther_diagnostics/cmake/SuperBuild.cmake b/husarion_ugv_diagnostics/cmake/SuperBuild.cmake similarity index 97% rename from panther_diagnostics/cmake/SuperBuild.cmake rename to husarion_ugv_diagnostics/cmake/SuperBuild.cmake index 4370b4cdd..83fdadbb3 100644 --- a/panther_diagnostics/cmake/SuperBuild.cmake +++ b/husarion_ugv_diagnostics/cmake/SuperBuild.cmake @@ -30,7 +30,7 @@ ExternalProject_Add( BUILD_IN_SOURCE 1) ExternalProject_Add( - ep_panther_diagnostics + ep_husarion_ugv_diagnostics DEPENDS ${DEPENDENCIES} SOURCE_DIR ${PROJECT_SOURCE_DIR} CMAKE_ARGS -DUSE_SUPERBUILD=OFF diff --git a/panther_diagnostics/config/system_monitor.yaml b/husarion_ugv_diagnostics/config/system_monitor.yaml similarity index 100% rename from panther_diagnostics/config/system_monitor.yaml rename to husarion_ugv_diagnostics/config/system_monitor.yaml diff --git a/panther_diagnostics/include/panther_diagnostics/filesystem.hpp b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/filesystem.hpp similarity index 93% rename from panther_diagnostics/include/panther_diagnostics/filesystem.hpp rename to husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/filesystem.hpp index fa2291d62..178253124 100644 --- a/panther_diagnostics/include/panther_diagnostics/filesystem.hpp +++ b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/filesystem.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_DIAGNOSTICS_FILESYSTEM_HPP_ -#define PANTHER_DIAGNOSTICS_FILESYSTEM_HPP_ +#ifndef HUSARION_UGV_DIAGNOSTICS_FILESYSTEM_HPP_ +#define HUSARION_UGV_DIAGNOSTICS_FILESYSTEM_HPP_ #include #include -namespace panther_diagnostics +namespace husarion_ugv_diagnostics { /** @@ -110,6 +110,6 @@ class Filesystem : public FilesystemInterface } }; -} // namespace panther_diagnostics +} // namespace husarion_ugv_diagnostics -#endif // PANTHER_DIAGNOSTICS_FILESYSTEM_HPP_ +#endif // HUSARION_UGV_DIAGNOSTICS_FILESYSTEM_HPP_ diff --git a/panther_diagnostics/include/panther_diagnostics/system_monitor_node.hpp b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp similarity index 87% rename from panther_diagnostics/include/panther_diagnostics/system_monitor_node.hpp rename to husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp index c840a246b..0532822f6 100644 --- a/panther_diagnostics/include/panther_diagnostics/system_monitor_node.hpp +++ b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/system_monitor_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_DIAGNOSTICS_SYSTEM_MONITOR_NODE_HPP_ -#define PANTHER_DIAGNOSTICS_SYSTEM_MONITOR_NODE_HPP_ +#ifndef HUSARION_UGV_DIAGNOSTICS_SYSTEM_MONITOR_NODE_HPP_ +#define HUSARION_UGV_DIAGNOSTICS_SYSTEM_MONITOR_NODE_HPP_ #include @@ -24,12 +24,12 @@ #include "system_monitor_parameters.hpp" -#include "panther_diagnostics/filesystem.hpp" -#include "panther_diagnostics/types.hpp" +#include "husarion_ugv_diagnostics/filesystem.hpp" +#include "husarion_ugv_diagnostics/types.hpp" using namespace std::chrono_literals; -namespace panther_diagnostics +namespace husarion_ugv_diagnostics { class SystemMonitorNode : public rclcpp::Node @@ -81,5 +81,5 @@ class SystemMonitorNode : public rclcpp::Node static constexpr char kTemperatureInfoFilename[] = "/sys/class/thermal/thermal_zone0/temp"; static constexpr char kRootDirectory[] = "/"; }; -} // namespace panther_diagnostics -#endif // PANTHER_DIAGNOSTICS_SYSTEM_MONITOR_NODE_HPP_ +} // namespace husarion_ugv_diagnostics +#endif // HUSARION_UGV_DIAGNOSTICS_SYSTEM_MONITOR_NODE_HPP_ diff --git a/panther_diagnostics/include/panther_diagnostics/types.hpp b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/types.hpp similarity index 82% rename from panther_diagnostics/include/panther_diagnostics/types.hpp rename to husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/types.hpp index 1ed2c88c7..4108b56dc 100644 --- a/panther_diagnostics/include/panther_diagnostics/types.hpp +++ b/husarion_ugv_diagnostics/include/husarion_ugv_diagnostics/types.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_DIAGNOSTICS_TYPES_HPP_ -#define PANTHER_DIAGNOSTICS_TYPES_HPP_ +#ifndef HUSARION_UGV_DIAGNOSTICS_TYPES_HPP_ +#define HUSARION_UGV_DIAGNOSTICS_TYPES_HPP_ #include -namespace panther_diagnostics +namespace husarion_ugv_diagnostics { /** @@ -35,6 +35,6 @@ struct SystemStatus float disk_usage; }; -} // namespace panther_diagnostics +} // namespace husarion_ugv_diagnostics -#endif // PANTHER_DIAGNOSTICS_TYPES_HPP_ +#endif // HUSARION_UGV_DIAGNOSTICS_TYPES_HPP_ diff --git a/panther_diagnostics/launch/system_monitor.launch.py b/husarion_ugv_diagnostics/launch/system_monitor.launch.py similarity index 97% rename from panther_diagnostics/launch/system_monitor.launch.py rename to husarion_ugv_diagnostics/launch/system_monitor.launch.py index e2d2ab706..34a82815f 100644 --- a/panther_diagnostics/launch/system_monitor.launch.py +++ b/husarion_ugv_diagnostics/launch/system_monitor.launch.py @@ -29,7 +29,7 @@ def generate_launch_description(): ) system_monitor_node = Node( - package="panther_diagnostics", + package="husarion_ugv_diagnostics", executable="system_monitor_node", name="system_monitor", namespace=namespace, diff --git a/panther_diagnostics/package.xml b/husarion_ugv_diagnostics/package.xml similarity index 87% rename from panther_diagnostics/package.xml rename to husarion_ugv_diagnostics/package.xml index 9f827b6d8..fe6258e05 100644 --- a/panther_diagnostics/package.xml +++ b/husarion_ugv_diagnostics/package.xml @@ -1,9 +1,9 @@ - panther_diagnostics + husarion_ugv_diagnostics 2.1.1 - Package for diagnosting usage of OS on the Panther Robot + Package for diagnosting usage of OS on the Husarion UGV robot Husarion Apache License 2.0 @@ -20,8 +20,8 @@ diagnostic_msgs diagnostic_updater generate_parameter_library + husarion_ugv_utils panther_msgs - panther_utils rclcpp std_msgs diff --git a/panther_diagnostics/src/main.cpp b/husarion_ugv_diagnostics/src/main.cpp similarity index 80% rename from panther_diagnostics/src/main.cpp rename to husarion_ugv_diagnostics/src/main.cpp index 8d09517f6..61cb38cca 100644 --- a/panther_diagnostics/src/main.cpp +++ b/husarion_ugv_diagnostics/src/main.cpp @@ -18,15 +18,15 @@ #include -#include "panther_diagnostics/filesystem.hpp" -#include "panther_diagnostics/system_monitor_node.hpp" +#include "husarion_ugv_diagnostics/filesystem.hpp" +#include "husarion_ugv_diagnostics/system_monitor_node.hpp" int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto filesystem = std::make_shared(); - auto system_monitor_node = std::make_shared( + auto filesystem = std::make_shared(); + auto system_monitor_node = std::make_shared( "system_monitor", filesystem); try { diff --git a/panther_diagnostics/src/system_monitor_node.cpp b/husarion_ugv_diagnostics/src/system_monitor_node.cpp similarity index 89% rename from panther_diagnostics/src/system_monitor_node.cpp rename to husarion_ugv_diagnostics/src/system_monitor_node.cpp index bc921a75d..f25bcbe3e 100644 --- a/panther_diagnostics/src/system_monitor_node.cpp +++ b/husarion_ugv_diagnostics/src/system_monitor_node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_diagnostics/system_monitor_node.hpp" +#include "husarion_ugv_diagnostics/system_monitor_node.hpp" #include #include @@ -24,13 +24,13 @@ #include "panther_msgs/msg/system_status.hpp" -#include "panther_utils/common_utilities.hpp" -#include "panther_utils/ros_utils.hpp" +#include "husarion_ugv_utils/common_utilities.hpp" +#include "husarion_ugv_utils/ros_utils.hpp" -#include "panther_diagnostics/filesystem.hpp" -#include "panther_diagnostics/types.hpp" +#include "husarion_ugv_diagnostics/filesystem.hpp" +#include "husarion_ugv_diagnostics/types.hpp" -namespace panther_diagnostics +namespace husarion_ugv_diagnostics { SystemMonitorNode::SystemMonitorNode( @@ -101,7 +101,7 @@ float SystemMonitorNode::GetCPUMeanUsage(const std::vector & usages) cons }); auto sum = std::accumulate(usages.begin(), usages.end(), 0.0); - auto mean_usage = panther_utils::common_utilities::SetPrecision(sum / usages.size(), 2); + auto mean_usage = husarion_ugv_utils::common_utilities::SetPrecision(sum / usages.size(), 2); return mean_usage; } @@ -112,7 +112,7 @@ float SystemMonitorNode::GetCPUTemperature() const try { const auto temperature_str = filesystem_->ReadFile(kTemperatureInfoFilename); - temperature = panther_utils::common_utilities::SetPrecision( + temperature = husarion_ugv_utils::common_utilities::SetPrecision( std::stof(temperature_str) / 1000.0, 2); } catch (const std::exception & e) { RCLCPP_ERROR_STREAM( @@ -127,7 +127,8 @@ float SystemMonitorNode::GetRAMUsage() const int total = 0, free = 0, available = 0; uprofile::getSystemMemory(total, available, free); - const auto ram_usage = panther_utils::common_utilities::CountPercentage(total - available, total); + const auto ram_usage = husarion_ugv_utils::common_utilities::CountPercentage( + total - available, total); return ram_usage; } @@ -138,7 +139,8 @@ float SystemMonitorNode::GetDiskUsage() const try { const auto capacity = filesystem_->GetSpaceCapacity(kRootDirectory); const auto available = filesystem_->GetSpaceAvailable(kRootDirectory); - disk_usage = panther_utils::common_utilities::CountPercentage(capacity - available, capacity); + disk_usage = husarion_ugv_utils::common_utilities::CountPercentage( + capacity - available, capacity); } catch (const std::exception & e) { RCLCPP_ERROR_STREAM( this->get_logger(), "An exception occurred while reading disk usage: " << e.what()); @@ -196,4 +198,4 @@ void SystemMonitorNode::DiagnoseSystem(diagnostic_updater::DiagnosticStatusWrapp status.summary(error_level, message); } -} // namespace panther_diagnostics +} // namespace husarion_ugv_diagnostics diff --git a/panther_diagnostics/test/integration/system_monitor_node.test.py b/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py similarity index 97% rename from panther_diagnostics/test/integration/system_monitor_node.test.py rename to husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py index dc895713f..53b34bd49 100644 --- a/panther_diagnostics/test/integration/system_monitor_node.test.py +++ b/husarion_ugv_diagnostics/test/integration/system_monitor_node.test.py @@ -30,7 +30,7 @@ def generate_test_description(): system_monitor_node = Node( - package="panther_diagnostics", + package="husarion_ugv_diagnostics", executable="system_monitor_node", ) diff --git a/panther_diagnostics/test/unit/test_filesystem.cpp b/husarion_ugv_diagnostics/test/unit/test_filesystem.cpp similarity index 91% rename from panther_diagnostics/test/unit/test_filesystem.cpp rename to husarion_ugv_diagnostics/test/unit/test_filesystem.cpp index 3e9c87553..24f7a6540 100644 --- a/panther_diagnostics/test/unit/test_filesystem.cpp +++ b/husarion_ugv_diagnostics/test/unit/test_filesystem.cpp @@ -18,7 +18,7 @@ #include #include -#include "panther_diagnostics/filesystem.hpp" +#include "husarion_ugv_diagnostics/filesystem.hpp" class TestFilesystem : public testing::Test { @@ -29,12 +29,13 @@ class TestFilesystem : public testing::Test void RemoveTestFile(const std::string & file_path); protected: - std::shared_ptr filesystem_; + std::shared_ptr filesystem_; static constexpr char kDummyString[] = "Hello World!"; }; -TestFilesystem::TestFilesystem() : filesystem_(std::make_shared()) +TestFilesystem::TestFilesystem() +: filesystem_(std::make_shared()) { } diff --git a/panther_diagnostics/test/unit/test_system_monitor_node.cpp b/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp similarity index 83% rename from panther_diagnostics/test/unit/test_system_monitor_node.cpp rename to husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp index 8c93ff248..dd6ad0538 100644 --- a/panther_diagnostics/test/unit/test_system_monitor_node.cpp +++ b/husarion_ugv_diagnostics/test/unit/test_system_monitor_node.cpp @@ -20,10 +20,10 @@ #include #include -#include "panther_diagnostics/filesystem.hpp" -#include "panther_diagnostics/system_monitor_node.hpp" +#include "husarion_ugv_diagnostics/filesystem.hpp" +#include "husarion_ugv_diagnostics/system_monitor_node.hpp" -class MockFilesystem : public panther_diagnostics::FilesystemInterface +class MockFilesystem : public husarion_ugv_diagnostics::FilesystemInterface { public: MOCK_METHOD( @@ -35,38 +35,38 @@ class MockFilesystem : public panther_diagnostics::FilesystemInterface MOCK_METHOD(std::string, ReadFile, (const std::string & file_path), (const, override)); }; -class SystemMonitorNodeWrapper : public panther_diagnostics::SystemMonitorNode +class SystemMonitorNodeWrapper : public husarion_ugv_diagnostics::SystemMonitorNode { public: SystemMonitorNodeWrapper(std::shared_ptr filesystem) - : panther_diagnostics::SystemMonitorNode("test_system_statics", filesystem) + : husarion_ugv_diagnostics::SystemMonitorNode("test_system_statics", filesystem) { } std::vector GetCoresUsages() const { - return panther_diagnostics::SystemMonitorNode::GetCoresUsages(); + return husarion_ugv_diagnostics::SystemMonitorNode::GetCoresUsages(); } float GetCPUMeanUsage(const std::vector & usages) const { - return panther_diagnostics::SystemMonitorNode::GetCPUMeanUsage(usages); + return husarion_ugv_diagnostics::SystemMonitorNode::GetCPUMeanUsage(usages); } float GetCPUTemperature() const { - return panther_diagnostics::SystemMonitorNode::GetCPUTemperature(); + return husarion_ugv_diagnostics::SystemMonitorNode::GetCPUTemperature(); } - float GetRAMUsage() const { return panther_diagnostics::SystemMonitorNode::GetRAMUsage(); } + float GetRAMUsage() const { return husarion_ugv_diagnostics::SystemMonitorNode::GetRAMUsage(); } - float GetDiskUsage() const { return panther_diagnostics::SystemMonitorNode::GetDiskUsage(); } + float GetDiskUsage() const { return husarion_ugv_diagnostics::SystemMonitorNode::GetDiskUsage(); } panther_msgs::msg::SystemStatus SystemStatusToMessage( - const panther_diagnostics::SystemStatus & status) + const husarion_ugv_diagnostics::SystemStatus & status) { - return panther_diagnostics::SystemMonitorNode::SystemStatusToMessage(status); + return husarion_ugv_diagnostics::SystemMonitorNode::SystemStatusToMessage(status); } }; @@ -160,7 +160,7 @@ TEST_F(TestSystemMonitorNode, GetDiskUsageInvalidFilesystem) TEST_F(TestSystemMonitorNode, SystemStatusToMessage) { - panther_diagnostics::SystemStatus test_status; + husarion_ugv_diagnostics::SystemStatus test_status; test_status.core_usages = {50.0, 50.0, 50.0}; test_status.cpu_mean_usage = 50.0; test_status.cpu_temperature = 36.6; diff --git a/panther_gazebo/CHANGELOG.rst b/husarion_ugv_gazebo/CHANGELOG.rst similarity index 100% rename from panther_gazebo/CHANGELOG.rst rename to husarion_ugv_gazebo/CHANGELOG.rst diff --git a/panther_gazebo/CMakeLists.txt b/husarion_ugv_gazebo/CMakeLists.txt similarity index 82% rename from panther_gazebo/CMakeLists.txt rename to husarion_ugv_gazebo/CMakeLists.txt index cae0aaa39..ae06fd9c3 100644 --- a/panther_gazebo/CMakeLists.txt +++ b/husarion_ugv_gazebo/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.10.2) -project(panther_gazebo) +project(husarion_ugv_gazebo) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) @@ -28,21 +28,21 @@ find_package(Qt5 REQUIRED COMPONENTS Core Quick QuickControls2) include_directories(include ${Qt5Core_INCLUDE_DIRS} ${Qt5Qml_INCLUDE_DIRS} ${Qt5Quick_INCLUDE_DIRS} ${Qt5QuickControls2_INCLUDE_DIRS}) -add_library(panther_simulation_plugins SHARED src/gz_panther_system.cpp) +add_library(estop_system_plugins SHARED src/estop_system.cpp) ament_target_dependencies( - panther_simulation_plugins + estop_system_plugins hardware_interface ign_ros2_control rclcpp rclcpp_lifecycle std_msgs std_srvs) -target_link_libraries(panther_simulation_plugins ignition-gazebo6) +target_link_libraries(estop_system_plugins ignition-gazebo6) set(CMAKE_AUTOMOC ON) qt5_add_resources(resources_rcc src/gui/EStop.qrc) -add_library(EStop SHARED include/panther_gazebo/gui/e_stop.hpp +add_library(EStop SHARED include/husarion_ugv_gazebo/gui/e_stop.hpp src/gui/e_stop.cpp ${resources_rcc}) ament_target_dependencies(EStop rclcpp std_srvs) target_link_libraries( @@ -60,7 +60,7 @@ target_link_libraries(LEDStrip ignition-gazebo6 ignition-msgs8 ignition-plugin1 ignition-transport11) install( - TARGETS panther_simulation_plugins + TARGETS estop_system_plugins RUNTIME DESTINATION bin LIBRARY DESTINATION lib ARCHIVE DESTINATION lib) @@ -86,8 +86,7 @@ endif() ament_export_include_directories(include) -pluginlib_export_plugin_description_file(ign_ros2_control - panther_simulation_plugins.xml) +pluginlib_export_plugin_description_file(ign_ros2_control plugins.xml) ament_environment_hooks( "${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.sh.in") diff --git a/panther_gazebo/CONFIGURATION.md b/husarion_ugv_gazebo/CONFIGURATION.md similarity index 71% rename from panther_gazebo/CONFIGURATION.md rename to husarion_ugv_gazebo/CONFIGURATION.md index d83baf523..3ad174b36 100644 --- a/panther_gazebo/CONFIGURATION.md +++ b/husarion_ugv_gazebo/CONFIGURATION.md @@ -1,8 +1,8 @@ -# panther_gazebo +# husarion_ugv_gazebo ## Use of GPS in Simulation -The NavSat system is utilized to publish the Panther robot's position within the Gazebo world. It manages navigation satellite sensors, such as GPS, which report position and velocity in spherical coordinates (latitude/longitude) through Ignition Transport. +The NavSat system is utilized to publish the robot's position within the Gazebo world. It manages navigation satellite sensors, such as GPS, which report position and velocity in spherical coordinates (latitude/longitude) through Ignition Transport. The NavSat sensors requires the spherical coordinates of the world origin to be configured. This configuration can be accomplished, for instance, by employing the `` tag within the world's SDF or by utilizing the Ignition `/world/world_name/set_spherical_coordinates` service. @@ -33,12 +33,12 @@ To obtain GPS data in Ignition, follow these steps: ## Linear Battery Plugin -It is possible to simulate the battery operation of the Panther robot. By default, this feature is disabled, but you can enable it by setting the `simulate_discharging` parameter to `true` in the `battery_plugin.yaml` file or in the file pointed to by the `battery_config_path` parameter. Below, you will find the plugin parameters that enable battery simulation. +It is possible to simulate the battery operation of the simulated robot. By default, this feature is disabled, but you can enable it by setting the `simulate_discharging` parameter to `true` in the `battery_plugin.yaml` file or in the file pointed to by the `battery_config_path` parameter. Below, you will find the plugin parameters that enable battery simulation. - `simulate_discharging` [*bool*, default: **false**]: Enables battery simulation. If set to `true`, the battery will discharge **at a constant rate** (regardless of joint torque), and if it depletes completely, the robot will stop moving. When set to `false`, the battery will not discharge, but the battery status information will still be published on the `battery/battery_status` topic. - `initial_charge_percentage` [*float*, default: **70.0**]: Sets the initial charge percentage of the battery. - `charging_time` [*float*, default: **6.0**]: Specifies the charging time for the battery in hours. -- `power_load` [*float*, default: **120.0**]: Represents the average power load during normal operation **[W]** and is initially set to 120.0 W. With the default power load of 120.0 W, the robot can operate for up to 8 hours. When the `simulate_discharging` parameter is set to `false`, this value defaults to 0.0 W. Users are encouraged to customize this value to match their specific requirements. For more information on Panther power consumption, please refer to [Panther Battery & Charging Documentation](https://husarion.com/manuals/panther/#battery--charging). +- `power_load` [*float*, default: **120.0**]: Represents the average power load during normal operation **[W]** and is initially set to 120.0 W. With the default power load of 120.0 W, the robot can operate for up to 8 hours. When the `simulate_discharging` parameter is set to `false`, this value defaults to 0.0 W. Users are encouraged to customize this value to match their specific requirements. For more information on robot power consumption, please refer to [Battery & Charging Documentation](https://husarion.com/manuals/panther/#battery--charging). > [!NOTE] > @@ -51,11 +51,11 @@ Unfortunately, there is no straightforward way to exchange `LinearBatteryPlugin` You can start the charging process by calling the Ignition service: ```bash -ign service --service /model/panther/battery/battery/recharge/start --reqtype ignition.msgs.Boolean --reptype ignition.msgs.Empty --req '' --timeout 0 +ign service --service /model/{robot_model}/battery/battery/recharge/start --reqtype ignition.msgs.Boolean --reptype ignition.msgs.Empty --req '' --timeout 0 ``` and stop it using: ```bash -ign service --service /model/panther/battery/battery/recharge/stop --reqtype ignition.msgs.Boolean --reptype ignition.msgs.Empty --req '' --timeout 0 +ign service --service /model/{robot_model}/battery/battery/recharge/stop --reqtype ignition.msgs.Boolean --reptype ignition.msgs.Empty --req '' --timeout 0 ``` diff --git a/panther_gazebo/README.md b/husarion_ugv_gazebo/README.md similarity index 98% rename from panther_gazebo/README.md rename to husarion_ugv_gazebo/README.md index 7a8189153..3b573404b 100644 --- a/panther_gazebo/README.md +++ b/husarion_ugv_gazebo/README.md @@ -1,4 +1,4 @@ -# panther_gazebo +# husarion_ugv_gazebo The package contains a launch file and source files used to run the robot simulation in Gazebo. The simulator tries to reproduce the behavior of a real robot as much as possible, including the provision of an analogous ROS_API. @@ -26,7 +26,7 @@ The package contains a launch file and source files used to run the robot simula - `hardware/e_stop_reset` [*std_srvs/Trigger*]: Resets E-stop. - `hardware/e_stop_trigger` [*std_srvs/Trigger*]: Triggers E-stop. -### GzPantherSystem +### EStopSystem Plugin based on `ign_system` is responsible for handling sensor interfaces (only IMU for now) and sending requests for joints compatible with `ros2_control`. Plugin also adds E-Stop support. diff --git a/panther_gazebo/config/battery_plugin.yaml b/husarion_ugv_gazebo/config/battery_plugin.yaml similarity index 82% rename from panther_gazebo/config/battery_plugin.yaml rename to husarion_ugv_gazebo/config/battery_plugin.yaml index 45eaac5ed..2564ebc3d 100644 --- a/panther_gazebo/config/battery_plugin.yaml +++ b/husarion_ugv_gazebo/config/battery_plugin.yaml @@ -1,6 +1,6 @@ # Parameters for the Gazebo LinearBatteryPlugin -# For more information on Panther power consumption, please refer to: -# https://husarion.com/manuals/panther/#battery--charging +# For more information on robots power consumption, please refer to: +# Panther: https://husarion.com/manuals/panther/#battery--charging # If set to true, the battery will discharge and if it depletes completely, the robot will stop moving. simulate_discharging: false diff --git a/panther_gazebo/config/gz_bridge.yaml b/husarion_ugv_gazebo/config/gz_bridge.yaml similarity index 100% rename from panther_gazebo/config/gz_bridge.yaml rename to husarion_ugv_gazebo/config/gz_bridge.yaml diff --git a/panther_gazebo/config/teleop_with_estop.config b/husarion_ugv_gazebo/config/teleop_with_estop.config similarity index 100% rename from panther_gazebo/config/teleop_with_estop.config rename to husarion_ugv_gazebo/config/teleop_with_estop.config diff --git a/panther_gazebo/hooks/panther_gazebo.sh.in b/husarion_ugv_gazebo/hooks/husarion_ugv_gazebo.sh.in similarity index 100% rename from panther_gazebo/hooks/panther_gazebo.sh.in rename to husarion_ugv_gazebo/hooks/husarion_ugv_gazebo.sh.in diff --git a/panther_gazebo/include/panther_gazebo/gz_panther_system.hpp b/husarion_ugv_gazebo/include/husarion_ugv_gazebo/estop_system.hpp similarity index 90% rename from panther_gazebo/include/panther_gazebo/gz_panther_system.hpp rename to husarion_ugv_gazebo/include/husarion_ugv_gazebo/estop_system.hpp index 6978fa716..3cb4742bc 100644 --- a/panther_gazebo/include/panther_gazebo/gz_panther_system.hpp +++ b/husarion_ugv_gazebo/include/husarion_ugv_gazebo/estop_system.hpp @@ -13,8 +13,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_GAZEBO_GZ_PANTHER_SYSTEM -#define PANTHER_GAZEBO_GZ_PANTHER_SYSTEM +#ifndef HUSARION_UGV_GAZEBO_ESTOP_SYSTEM +#define HUSARION_UGV_GAZEBO_ESTOP_SYSTEM #include @@ -27,7 +27,7 @@ #include #include -namespace panther_gazebo +namespace husarion_ugv_gazebo { using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; using BoolMsg = std_msgs::msg::Bool; @@ -38,7 +38,7 @@ using TriggerSrv = std_srvs::srv::Trigger; * `hardware_interface::SystemInterface`. This class inherits `ign_ros2_control::IgnitionSystem` * and implements additional functionalities like E-stop handling. */ -class GzPantherSystem : public ign_ros2_control::IgnitionSystem +class EStopSystem : public ign_ros2_control::IgnitionSystem { public: CallbackReturn on_init(const hardware_interface::HardwareInfo & system_info) override; @@ -69,6 +69,6 @@ class GzPantherSystem : public ign_ros2_control::IgnitionSystem rclcpp::Service::SharedPtr e_stop_trigger_service_; }; -} // namespace panther_gazebo +} // namespace husarion_ugv_gazebo -#endif // PANTHER_GAZEBO_GZ_PANTHER_SYSTEM +#endif // HUSARION_UGV_GAZEBO_ESTOP_SYSTEM diff --git a/panther_gazebo/include/panther_gazebo/gui/e_stop.hpp b/husarion_ugv_gazebo/include/husarion_ugv_gazebo/gui/e_stop.hpp similarity index 89% rename from panther_gazebo/include/panther_gazebo/gui/e_stop.hpp rename to husarion_ugv_gazebo/include/husarion_ugv_gazebo/gui/e_stop.hpp index 055db7e16..962f5b207 100644 --- a/panther_gazebo/include/panther_gazebo/gui/e_stop.hpp +++ b/husarion_ugv_gazebo/include/husarion_ugv_gazebo/gui/e_stop.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_GAZEBO_GUI_E_STOP_HPP_ -#define PANTHER_GAZEBO_GUI_E_STOP_HPP_ +#ifndef HUSARION_UGV_GAZEBO_GUI_E_STOP_HPP_ +#define HUSARION_UGV_GAZEBO_GUI_E_STOP_HPP_ #include @@ -23,7 +23,7 @@ #include -namespace panther_gazebo +namespace husarion_ugv_gazebo { class EStop : public ignition::gui::Plugin @@ -59,6 +59,6 @@ protected slots: rclcpp::Client::SharedPtr e_stop_reset_client_; rclcpp::Client::SharedPtr e_stop_trigger_client_; }; -} // namespace panther_gazebo +} // namespace husarion_ugv_gazebo -#endif // PANTHER_GAZEBO_GUI_E_STOP_HPP_ +#endif // HUSARION_UGV_GAZEBO_GUI_E_STOP_HPP_ diff --git a/panther_gazebo/include/panther_gazebo/led_strip.hpp b/husarion_ugv_gazebo/include/husarion_ugv_gazebo/led_strip.hpp similarity index 96% rename from panther_gazebo/include/panther_gazebo/led_strip.hpp rename to husarion_ugv_gazebo/include/husarion_ugv_gazebo/led_strip.hpp index 0f0945ea6..74d764449 100644 --- a/panther_gazebo/include/panther_gazebo/led_strip.hpp +++ b/husarion_ugv_gazebo/include/husarion_ugv_gazebo/led_strip.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_GAZEBO_LED_STRIP_HPP_ -#define PANTHER_GAZEBO_LED_STRIP_HPP_ +#ifndef HUSARION_UGV_GAZEBO_LED_STRIP_HPP_ +#define HUSARION_UGV_GAZEBO_LED_STRIP_HPP_ #include #include @@ -33,7 +33,7 @@ #include #include -namespace panther_gazebo +namespace husarion_ugv_gazebo { /** @@ -144,6 +144,6 @@ class LEDStrip : public gz::sim::System, 1)}; // Avoid initialization errors when the robot is not yet spawned on the scene. }; -} // namespace panther_gazebo +} // namespace husarion_ugv_gazebo -#endif // PANTHER_GAZEBO_LED_STRIP_HPP_ +#endif // HUSARION_UGV_GAZEBO_LED_STRIP_HPP_ diff --git a/panther_gazebo/launch/simulate_robot.launch.py b/husarion_ugv_gazebo/launch/simulate_robot.launch.py similarity index 91% rename from panther_gazebo/launch/simulate_robot.launch.py rename to husarion_ugv_gazebo/launch/simulate_robot.launch.py index 2bd4f822b..22c84d2b2 100644 --- a/panther_gazebo/launch/simulate_robot.launch.py +++ b/husarion_ugv_gazebo/launch/simulate_robot.launch.py @@ -51,7 +51,7 @@ def generate_launch_description(): "This configuration is intended for use in simulations only." ), default_value=PathJoinSubstitution( - [FindPackageShare("panther_gazebo"), "config", "battery_plugin.yaml"] + [FindPackageShare("husarion_ugv_gazebo"), "config", "battery_plugin.yaml"] ), ) @@ -65,8 +65,8 @@ def generate_launch_description(): ), description=( "Additional components configuration file. Components described in this file " - "are dynamically included in Panther's urdf." - "Panther options are described here " + "are dynamically included in robot's URDF." + "Available options are described in the manual: " "https://husarion.com/manuals/panther/panther-options/" ), ) @@ -75,7 +75,7 @@ def generate_launch_description(): declare_gz_bridge_config_path_arg = DeclareLaunchArgument( "gz_bridge_config_path", default_value=PathJoinSubstitution( - [FindPackageShare("panther_gazebo"), "config", "gz_bridge.yaml"] + [FindPackageShare("husarion_ugv_gazebo"), "config", "gz_bridge.yaml"] ), description="Path to the parameter_bridge configuration file.", ) @@ -107,7 +107,7 @@ def generate_launch_description(): spawn_robot_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_gazebo"), "launch", "spawn_robot.launch.py"] + [FindPackageShare("husarion_ugv_gazebo"), "launch", "spawn_robot.launch.py"] ) ), launch_arguments={ @@ -119,7 +119,7 @@ def generate_launch_description(): lights_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_lights"), "launch", "lights.launch.py"] + [FindPackageShare("husarion_ugv_lights"), "launch", "lights.launch.py"] ) ), launch_arguments={"namespace": namespace, "use_sim": "True"}.items(), @@ -128,7 +128,7 @@ def generate_launch_description(): manager_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( - [FindPackageShare("panther_manager"), "launch", "manager.launch.py"] + [FindPackageShare("husarion_ugv_manager"), "launch", "manager.launch.py"] ) ), launch_arguments={"namespace": namespace, "use_sim": "True"}.items(), @@ -138,7 +138,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( PathJoinSubstitution( [ - FindPackageShare("panther_controller"), + FindPackageShare("husarion_ugv_controller"), "launch", "controller.launch.py", ] @@ -155,7 +155,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( PathJoinSubstitution( [ - FindPackageShare("panther_localization"), + FindPackageShare("husarion_ugv_localization"), "launch", "localization.launch.py", ] @@ -192,7 +192,7 @@ def generate_launch_description(): gz_bridge = Node( package="ros_gz_bridge", executable="parameter_bridge", - name="panther_base_gz_bridge", + name="base_gz_bridge", parameters=[{"config_file": namespaced_gz_bridge_config_path}], namespace=namespace, emulate_tty=True, diff --git a/panther_gazebo/launch/simulation.launch.py b/husarion_ugv_gazebo/launch/simulation.launch.py similarity index 94% rename from panther_gazebo/launch/simulation.launch.py rename to husarion_ugv_gazebo/launch/simulation.launch.py index 5ea187207..cf2e78de3 100644 --- a/panther_gazebo/launch/simulation.launch.py +++ b/husarion_ugv_gazebo/launch/simulation.launch.py @@ -33,7 +33,7 @@ def generate_launch_description(): declare_gz_gui = DeclareLaunchArgument( "gz_gui", default_value=PathJoinSubstitution( - [FindPackageShare("panther_gazebo"), "config", "teleop_with_estop.config"] + [FindPackageShare("husarion_ugv_gazebo"), "config", "teleop_with_estop.config"] ), description="Run simulation with specific GUI layout.", ) @@ -63,7 +63,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( PathJoinSubstitution( [ - FindPackageShare("panther_gazebo"), + FindPackageShare("husarion_ugv_gazebo"), "launch", "simulate_robot.launch.py", ] diff --git a/panther_gazebo/launch/spawn_robot.launch.py b/husarion_ugv_gazebo/launch/spawn_robot.launch.py similarity index 98% rename from panther_gazebo/launch/spawn_robot.launch.py rename to husarion_ugv_gazebo/launch/spawn_robot.launch.py index 624586ba4..39a47a2cb 100644 --- a/panther_gazebo/launch/spawn_robot.launch.py +++ b/husarion_ugv_gazebo/launch/spawn_robot.launch.py @@ -16,6 +16,7 @@ import os +from husarion_ugv_utils.messages import welcome_msg from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource @@ -27,7 +28,6 @@ ) from launch_ros.actions import Node, SetUseSimTime from launch_ros.substitutions import FindPackageShare -from panther_utils.messages import welcome_msg def generate_launch_description(): diff --git a/panther_gazebo/package.xml b/husarion_ugv_gazebo/package.xml similarity index 93% rename from panther_gazebo/package.xml rename to husarion_ugv_gazebo/package.xml index faa23cdd3..186f663b7 100644 --- a/panther_gazebo/package.xml +++ b/husarion_ugv_gazebo/package.xml @@ -1,7 +1,7 @@ - panther_gazebo + husarion_ugv_gazebo 2.1.1 The panther_description package Husarion @@ -29,16 +29,16 @@ controller_manager husarion_gz_worlds + husarion_ugv_controller + husarion_ugv_lights + husarion_ugv_localization + husarion_ugv_manager + husarion_ugv_utils launch launch_ros lynx_description nav2_common - panther_controller panther_description - panther_lights - panther_localization - panther_manager - panther_utils robot_state_publisher ros_components_description ros_gz_bridge diff --git a/panther_gazebo/panther_simulation_plugins.xml b/husarion_ugv_gazebo/plugins.xml similarity index 62% rename from panther_gazebo/panther_simulation_plugins.xml rename to husarion_ugv_gazebo/plugins.xml index 7a0aef76c..e25a8bce3 100644 --- a/panther_gazebo/panther_simulation_plugins.xml +++ b/husarion_ugv_gazebo/plugins.xml @@ -1,7 +1,7 @@ - + Control joints position with E-Stop functionalities in Gazebo using ROS2. diff --git a/panther_gazebo/src/gz_panther_system.cpp b/husarion_ugv_gazebo/src/estop_system.cpp similarity index 82% rename from panther_gazebo/src/gz_panther_system.cpp rename to husarion_ugv_gazebo/src/estop_system.cpp index d705d716e..4f37923f9 100644 --- a/panther_gazebo/src/gz_panther_system.cpp +++ b/husarion_ugv_gazebo/src/estop_system.cpp @@ -28,7 +28,7 @@ #include #include -#include "panther_gazebo/gz_panther_system.hpp" +#include "husarion_ugv_gazebo/estop_system.hpp" struct jointData { @@ -94,10 +94,10 @@ class ign_ros2_control::IgnitionSystemPrivate double position_proportional_gain_; }; -namespace panther_gazebo +namespace husarion_ugv_gazebo { -CallbackReturn GzPantherSystem::on_init(const hardware_interface::HardwareInfo & system_info) +CallbackReturn EStopSystem::on_init(const hardware_interface::HardwareInfo & system_info) { if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; @@ -108,24 +108,24 @@ CallbackReturn GzPantherSystem::on_init(const hardware_interface::HardwareInfo & return CallbackReturn::SUCCESS; } -CallbackReturn GzPantherSystem::on_configure(const rclcpp_lifecycle::State & previous_state) +CallbackReturn EStopSystem::on_configure(const rclcpp_lifecycle::State & previous_state) { SetupEStop(); return hardware_interface::SystemInterface::on_configure(previous_state); } -CallbackReturn GzPantherSystem::on_activate(const rclcpp_lifecycle::State & previous_state) +CallbackReturn EStopSystem::on_activate(const rclcpp_lifecycle::State & previous_state) { PublishEStopStatus(); return hardware_interface::SystemInterface::on_activate(previous_state); } -CallbackReturn GzPantherSystem::on_deactivate(const rclcpp_lifecycle::State & previous_state) +CallbackReturn EStopSystem::on_deactivate(const rclcpp_lifecycle::State & previous_state) { return hardware_interface::SystemInterface::on_deactivate(previous_state); } -hardware_interface::return_type GzPantherSystem::write( +hardware_interface::return_type EStopSystem::write( const rclcpp::Time & time, const rclcpp::Duration & period) { if (e_stop_active_) { @@ -135,7 +135,7 @@ hardware_interface::return_type GzPantherSystem::write( return IgnitionSystem::write(time, period); } -void GzPantherSystem::SetupEStop() +void EStopSystem::SetupEStop() { e_stop_publisher_ = nh_->create_publisher( "~/e_stop", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); @@ -143,22 +143,22 @@ void GzPantherSystem::SetupEStop() e_stop_reset_service_ = nh_->create_service( "~/e_stop_reset", std::bind( - &GzPantherSystem::EStopResetCallback, this, std::placeholders::_1, std::placeholders::_2)); + &EStopSystem::EStopResetCallback, this, std::placeholders::_1, std::placeholders::_2)); e_stop_trigger_service_ = nh_->create_service( "~/e_stop_trigger", std::bind( - &GzPantherSystem::EStopTriggerCallback, this, std::placeholders::_1, std::placeholders::_2)); + &EStopSystem::EStopTriggerCallback, this, std::placeholders::_1, std::placeholders::_2)); } -void GzPantherSystem::PublishEStopStatus() +void EStopSystem::PublishEStopStatus() { std_msgs::msg::Bool e_stop_msg; e_stop_msg.data = e_stop_active_; e_stop_publisher_->publish(e_stop_msg); } -void GzPantherSystem::EStopResetCallback( +void EStopSystem::EStopResetCallback( const TriggerSrv::Request::SharedPtr & /*request*/, TriggerSrv::Response::SharedPtr response) { e_stop_active_ = false; @@ -167,7 +167,7 @@ void GzPantherSystem::EStopResetCallback( PublishEStopStatus(); } -void GzPantherSystem::EStopTriggerCallback( +void EStopSystem::EStopTriggerCallback( const TriggerSrv::Request::SharedPtr & /*request*/, TriggerSrv::Response::SharedPtr response) { e_stop_active_ = true; @@ -176,7 +176,7 @@ void GzPantherSystem::EStopTriggerCallback( PublishEStopStatus(); } -} // namespace panther_gazebo +} // namespace husarion_ugv_gazebo #include "pluginlib/class_list_macros.hpp" // NOLINT -PLUGINLIB_EXPORT_CLASS(panther_gazebo::GzPantherSystem, ign_ros2_control::IgnitionSystemInterface) +PLUGINLIB_EXPORT_CLASS(husarion_ugv_gazebo::EStopSystem, ign_ros2_control::IgnitionSystemInterface) diff --git a/panther_gazebo/src/gui/EStop.qml b/husarion_ugv_gazebo/src/gui/EStop.qml similarity index 100% rename from panther_gazebo/src/gui/EStop.qml rename to husarion_ugv_gazebo/src/gui/EStop.qml diff --git a/panther_gazebo/src/gui/EStop.qrc b/husarion_ugv_gazebo/src/gui/EStop.qrc similarity index 100% rename from panther_gazebo/src/gui/EStop.qrc rename to husarion_ugv_gazebo/src/gui/EStop.qrc diff --git a/panther_gazebo/src/gui/e_stop.cpp b/husarion_ugv_gazebo/src/gui/e_stop.cpp similarity index 94% rename from panther_gazebo/src/gui/e_stop.cpp rename to husarion_ugv_gazebo/src/gui/e_stop.cpp index ff4c30102..ffad684dd 100644 --- a/panther_gazebo/src/gui/e_stop.cpp +++ b/husarion_ugv_gazebo/src/gui/e_stop.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_gazebo/gui/e_stop.hpp" +#include "husarion_ugv_gazebo/gui/e_stop.hpp" #include @@ -23,7 +23,7 @@ #include -namespace panther_gazebo +namespace husarion_ugv_gazebo { EStop::EStop() : ignition::gui::Plugin() { rclcpp::init(0, nullptr); } @@ -90,6 +90,6 @@ void EStop::SetNamespace(const QString & ns) ignmsg << "Changed namespace to: " << namespace_ << std::endl; } -} // namespace panther_gazebo +} // namespace husarion_ugv_gazebo -IGNITION_ADD_PLUGIN(panther_gazebo::EStop, ignition::gui::Plugin) +IGNITION_ADD_PLUGIN(husarion_ugv_gazebo::EStop, ignition::gui::Plugin) diff --git a/panther_gazebo/src/led_strip.cpp b/husarion_ugv_gazebo/src/led_strip.cpp similarity index 97% rename from panther_gazebo/src/led_strip.cpp rename to husarion_ugv_gazebo/src/led_strip.cpp index c7820bb1f..c0984620c 100644 --- a/panther_gazebo/src/led_strip.cpp +++ b/husarion_ugv_gazebo/src/led_strip.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "panther_gazebo/led_strip.hpp" +#include "husarion_ugv_gazebo/led_strip.hpp" #include #include @@ -25,7 +25,7 @@ #include #include -namespace panther_gazebo +namespace husarion_ugv_gazebo { void LEDStrip::Configure( const gz::sim::Entity & entity, const std::shared_ptr & sdf, @@ -275,8 +275,8 @@ void LEDStrip::CreateMarker( node_.Request("/marker", marker_msg); } -} // namespace panther_gazebo +} // namespace husarion_ugv_gazebo IGNITION_ADD_PLUGIN( - panther_gazebo::LEDStrip, gz::sim::System, panther_gazebo::LEDStrip::ISystemConfigure, - panther_gazebo::LEDStrip::ISystemPreUpdate) + husarion_ugv_gazebo::LEDStrip, gz::sim::System, husarion_ugv_gazebo::LEDStrip::ISystemConfigure, + husarion_ugv_gazebo::LEDStrip::ISystemPreUpdate) diff --git a/panther_hardware_interfaces/CHANGELOG.rst b/husarion_ugv_hardware_interfaces/CHANGELOG.rst similarity index 100% rename from panther_hardware_interfaces/CHANGELOG.rst rename to husarion_ugv_hardware_interfaces/CHANGELOG.rst diff --git a/panther_hardware_interfaces/CMakeLists.txt b/husarion_ugv_hardware_interfaces/CMakeLists.txt similarity index 58% rename from panther_hardware_interfaces/CMakeLists.txt rename to husarion_ugv_hardware_interfaces/CMakeLists.txt index 1728bd37d..66d2aeff8 100644 --- a/panther_hardware_interfaces/CMakeLists.txt +++ b/husarion_ugv_hardware_interfaces/CMakeLists.txt @@ -8,7 +8,7 @@ if(USE_SUPERBUILD) include(cmake/SuperBuild.cmake) return() else() - project(panther_hardware_interfaces) + project(husarion_ugv_hardware_interfaces) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -24,7 +24,7 @@ set(PACKAGE_DEPENDENCIES hardware_interface imu_filter_madgwick panther_msgs - panther_utils + husarion_ugv_utils phidgets_api PkgConfig pluginlib @@ -52,31 +52,31 @@ pkg_check_modules(LIBGPIOD REQUIRED IMPORTED_TARGET libgpiodcxx) add_library( ${PROJECT_NAME} SHARED - src/panther_imu_sensor/panther_imu_sensor.cpp - src/panther_system/gpio/gpio_controller.cpp - src/panther_system/gpio/gpio_driver.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_driver.cpp - src/panther_system/robot_driver/roboteq_error_filter.cpp - src/panther_system/robot_driver/roboteq_robot_driver.cpp - src/panther_system/robot_driver/lynx_robot_driver.cpp - src/panther_system/robot_driver/panther_robot_driver.cpp - src/panther_system/system_e_stop.cpp - src/panther_system/system_ros_interface.cpp - src/panther_system/lynx_system.cpp - src/panther_system/panther_system.cpp - src/panther_system/ugv_system.cpp + src/phidget_imu_sensor/phidget_imu_sensor.cpp + src/robot_system/gpio/gpio_controller.cpp + src/robot_system/gpio/gpio_driver.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_driver.cpp + src/robot_system/robot_driver/roboteq_error_filter.cpp + src/robot_system/robot_driver/roboteq_robot_driver.cpp + src/robot_system/robot_driver/lynx_robot_driver.cpp + src/robot_system/robot_driver/panther_robot_driver.cpp + src/robot_system/system_e_stop.cpp + src/robot_system/system_ros_interface.cpp + src/robot_system/lynx_system.cpp + src/robot_system/panther_system.cpp + src/robot_system/ugv_system.cpp src/utils.cpp) ament_target_dependencies(${PROJECT_NAME} ${PACKAGE_DEPENDENCIES}) target_link_libraries(${PROJECT_NAME} PkgConfig::LIBLELY_COAPP PkgConfig::LIBGPIOD phidgets_spatial_parameters) -target_compile_definitions(${PROJECT_NAME} - PRIVATE "PANTHER_HARDWARE_INTERFACES_BUILDING_DLL") +target_compile_definitions( + ${PROJECT_NAME} PRIVATE "HUSARION_UGV_HARDWARE_INTERFACES_BUILDING_DLL") pluginlib_export_plugin_description_file(hardware_interface - panther_hardware_interfaces.xml) + husarion_ugv_hardware_interfaces.xml) install( TARGETS ${PROJECT_NAME} @@ -90,134 +90,135 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(ament_cmake_gmock REQUIRED) find_package(ros_testing REQUIRED) - find_package(panther_utils REQUIRED) + find_package(husarion_ugv_utils REQUIRED) install(DIRECTORY test/config DESTINATION share/${PROJECT_NAME}/test) ament_add_gtest(${PROJECT_NAME}_test_utils test/test_utils.cpp src/utils.cpp) - ament_add_gtest(${PROJECT_NAME}_test_panther_imu_sensor - test/panther_imu_sensor/test_panther_imu_sensor.cpp) + ament_add_gtest(${PROJECT_NAME}_test_phidget_imu_sensor + test/phidget_imu_sensor/test_phidget_imu_sensor.cpp) ament_target_dependencies( - ${PROJECT_NAME}_test_panther_imu_sensor hardware_interface rclcpp - panther_utils panther_msgs phidgets_api) - target_link_libraries(${PROJECT_NAME}_test_panther_imu_sensor ${PROJECT_NAME} + ${PROJECT_NAME}_test_phidget_imu_sensor hardware_interface rclcpp + husarion_ugv_utils panther_msgs phidgets_api) + target_link_libraries(${PROJECT_NAME}_test_phidget_imu_sensor ${PROJECT_NAME} phidgets_spatial_parameters) ament_add_gtest( ${PROJECT_NAME}_test_roboteq_error_filter - test/unit/panther_system/robot_driver/test_roboteq_error_filter.cpp - src/panther_system/robot_driver/roboteq_error_filter.cpp) + test/unit/robot_system/robot_driver/test_roboteq_error_filter.cpp + src/robot_system/robot_driver/roboteq_error_filter.cpp) ament_add_gtest( ${PROJECT_NAME}_test_roboteq_data_converters - test/unit/panther_system/robot_driver/test_roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp src/utils.cpp) + test/unit/robot_system/robot_driver/test_roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_roboteq_data_converters PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_data_converters - panther_msgs panther_utils) + panther_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_data_converters PkgConfig::LIBLELY_COAPP) ament_add_gtest( ${PROJECT_NAME}_test_canopen_manager - test/unit/panther_system/robot_driver/test_canopen_manager.cpp - src/panther_system/robot_driver/canopen_manager.cpp src/utils.cpp) + test/unit/robot_system/robot_driver/test_canopen_manager.cpp + src/robot_system/robot_driver/canopen_manager.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_canopen_manager PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_canopen_manager rclcpp - panther_msgs panther_utils) + panther_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_canopen_manager PkgConfig::LIBLELY_COAPP) ament_add_gtest( ${PROJECT_NAME}_test_roboteq_driver - test/unit/panther_system/robot_driver/test_roboteq_driver.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_driver.cpp + test/unit/robot_system/robot_driver/test_roboteq_driver.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_driver.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_roboteq_driver PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_driver rclcpp - panther_msgs panther_utils) + panther_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_driver PkgConfig::LIBLELY_COAPP) ament_add_gmock( ${PROJECT_NAME}_test_roboteq_robot_driver - test/unit/panther_system/robot_driver/test_roboteq_robot_driver.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_driver.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_robot_driver.cpp + test/unit/robot_system/robot_driver/test_roboteq_robot_driver.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_driver.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_robot_driver.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_roboteq_robot_driver PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_roboteq_robot_driver rclcpp - panther_msgs panther_utils) + panther_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_roboteq_robot_driver PkgConfig::LIBLELY_COAPP) ament_add_gmock( ${PROJECT_NAME}_test_lynx_robot_driver - test/unit/panther_system/robot_driver/test_lynx_robot_driver.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_driver.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_robot_driver.cpp - src/panther_system/robot_driver/lynx_robot_driver.cpp + test/unit/robot_system/robot_driver/test_lynx_robot_driver.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_driver.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_robot_driver.cpp + src/robot_system/robot_driver/lynx_robot_driver.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_lynx_robot_driver PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_lynx_robot_driver rclcpp - panther_msgs panther_utils) + panther_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_lynx_robot_driver PkgConfig::LIBLELY_COAPP) ament_add_gmock( ${PROJECT_NAME}_test_panther_robot_driver - test/unit/panther_system/robot_driver/test_panther_robot_driver.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_driver.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_robot_driver.cpp - src/panther_system/robot_driver/panther_robot_driver.cpp + test/unit/robot_system/robot_driver/test_panther_robot_driver.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_driver.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_robot_driver.cpp + src/robot_system/robot_driver/panther_robot_driver.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_panther_robot_driver PUBLIC $ $) ament_target_dependencies(${PROJECT_NAME}_test_panther_robot_driver rclcpp - panther_msgs panther_utils) + panther_msgs husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_panther_robot_driver PkgConfig::LIBLELY_COAPP) ament_add_gmock( ${PROJECT_NAME}_test_gpiod_controller - test/panther_system/gpio/test_gpio_controller.cpp - src/panther_system/gpio/gpio_controller.cpp - src/panther_system/gpio/gpio_driver.cpp) - ament_target_dependencies(${PROJECT_NAME}_test_gpiod_controller panther_utils) + test/robot_system/gpio/test_gpio_controller.cpp + src/robot_system/gpio/gpio_controller.cpp + src/robot_system/gpio/gpio_driver.cpp) + ament_target_dependencies(${PROJECT_NAME}_test_gpiod_controller + husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_gpiod_controller PkgConfig::LIBGPIOD) ament_add_gtest( ${PROJECT_NAME}_test_system_ros_interface - test/unit/panther_system/test_system_ros_interface.cpp - src/panther_system/system_ros_interface.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/gpio/gpio_controller.cpp + test/unit/robot_system/test_system_ros_interface.cpp + src/robot_system/system_ros_interface.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/gpio/gpio_controller.cpp src/utils.cpp) target_include_directories( ${PROJECT_NAME}_test_system_ros_interface @@ -228,7 +229,7 @@ if(BUILD_TESTING) diagnostic_updater rclcpp panther_msgs - panther_utils + husarion_ugv_utils realtime_tools std_srvs) target_link_libraries(${PROJECT_NAME}_test_system_ros_interface @@ -236,14 +237,14 @@ if(BUILD_TESTING) ament_add_gmock( ${PROJECT_NAME}_test_ugv_system - test/unit/panther_system/test_ugv_system.cpp - src/panther_system/gpio/gpio_controller.cpp - src/panther_system/gpio/gpio_driver.cpp - src/panther_system/system_e_stop.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_error_filter.cpp - src/panther_system/system_ros_interface.cpp - src/panther_system/ugv_system.cpp + test/unit/robot_system/test_ugv_system.cpp + src/robot_system/gpio/gpio_controller.cpp + src/robot_system/gpio/gpio_driver.cpp + src/robot_system/system_e_stop.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_error_filter.cpp + src/robot_system/system_ros_interface.cpp + src/robot_system/ugv_system.cpp src/utils.cpp) set_tests_properties(${PROJECT_NAME}_test_ugv_system PROPERTIES TIMEOUT 120) target_include_directories( @@ -256,7 +257,7 @@ if(BUILD_TESTING) hardware_interface rclcpp panther_msgs - panther_utils + husarion_ugv_utils std_msgs std_srvs) target_link_libraries(${PROJECT_NAME}_test_ugv_system @@ -264,19 +265,19 @@ if(BUILD_TESTING) ament_add_gmock( ${PROJECT_NAME}_test_lynx_system - test/unit/panther_system/test_lynx_system.cpp - src/panther_system/gpio/gpio_controller.cpp - src/panther_system/gpio/gpio_driver.cpp - src/panther_system/system_e_stop.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_robot_driver.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_driver.cpp - src/panther_system/robot_driver/roboteq_error_filter.cpp - src/panther_system/robot_driver/lynx_robot_driver.cpp - src/panther_system/system_ros_interface.cpp - src/panther_system/lynx_system.cpp - src/panther_system/ugv_system.cpp + test/unit/robot_system/test_lynx_system.cpp + src/robot_system/gpio/gpio_controller.cpp + src/robot_system/gpio/gpio_driver.cpp + src/robot_system/system_e_stop.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_robot_driver.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_driver.cpp + src/robot_system/robot_driver/roboteq_error_filter.cpp + src/robot_system/robot_driver/lynx_robot_driver.cpp + src/robot_system/system_ros_interface.cpp + src/robot_system/lynx_system.cpp + src/robot_system/ugv_system.cpp src/utils.cpp) set_tests_properties(${PROJECT_NAME}_test_lynx_system PROPERTIES TIMEOUT 120) target_include_directories( @@ -289,7 +290,7 @@ if(BUILD_TESTING) hardware_interface rclcpp panther_msgs - panther_utils + husarion_ugv_utils std_msgs std_srvs) target_link_libraries(${PROJECT_NAME}_test_lynx_system @@ -297,19 +298,19 @@ if(BUILD_TESTING) ament_add_gmock( ${PROJECT_NAME}_test_panther_system - test/unit/panther_system/test_panther_system.cpp - src/panther_system/gpio/gpio_controller.cpp - src/panther_system/gpio/gpio_driver.cpp - src/panther_system/system_e_stop.cpp - src/panther_system/robot_driver/canopen_manager.cpp - src/panther_system/robot_driver/roboteq_robot_driver.cpp - src/panther_system/robot_driver/roboteq_data_converters.cpp - src/panther_system/robot_driver/roboteq_driver.cpp - src/panther_system/robot_driver/roboteq_error_filter.cpp - src/panther_system/robot_driver/panther_robot_driver.cpp - src/panther_system/system_ros_interface.cpp - src/panther_system/panther_system.cpp - src/panther_system/ugv_system.cpp + test/unit/robot_system/test_panther_system.cpp + src/robot_system/gpio/gpio_controller.cpp + src/robot_system/gpio/gpio_driver.cpp + src/robot_system/system_e_stop.cpp + src/robot_system/robot_driver/canopen_manager.cpp + src/robot_system/robot_driver/roboteq_robot_driver.cpp + src/robot_system/robot_driver/roboteq_data_converters.cpp + src/robot_system/robot_driver/roboteq_driver.cpp + src/robot_system/robot_driver/roboteq_error_filter.cpp + src/robot_system/robot_driver/panther_robot_driver.cpp + src/robot_system/system_ros_interface.cpp + src/robot_system/panther_system.cpp + src/robot_system/ugv_system.cpp src/utils.cpp) set_tests_properties(${PROJECT_NAME}_test_panther_system PROPERTIES TIMEOUT 120) @@ -323,7 +324,7 @@ if(BUILD_TESTING) hardware_interface rclcpp panther_msgs - panther_utils + husarion_ugv_utils std_msgs std_srvs) target_link_libraries(${PROJECT_NAME}_test_panther_system @@ -332,8 +333,9 @@ if(BUILD_TESTING) # Integration tests option(TEST_INTEGRATION "Run integration tests" OFF) if(TEST_INTEGRATION) # Hardware integration ament_add_gtest(${PROJECT_NAME}_test_gpiod_driver - test/panther_system/gpio/test_gpio_driver.cpp) - ament_target_dependencies(${PROJECT_NAME}_test_gpiod_driver panther_utils) + test/robot_system/gpio/test_gpio_driver.cpp) + ament_target_dependencies(${PROJECT_NAME}_test_gpiod_driver + husarion_ugv_utils) target_link_libraries(${PROJECT_NAME}_test_gpiod_driver ${PROJECT_NAME} PkgConfig::LIBGPIOD) endif() diff --git a/panther_hardware_interfaces/CODE_STRUCTURE.md b/husarion_ugv_hardware_interfaces/CODE_STRUCTURE.md similarity index 100% rename from panther_hardware_interfaces/CODE_STRUCTURE.md rename to husarion_ugv_hardware_interfaces/CODE_STRUCTURE.md diff --git a/panther_hardware_interfaces/README.md b/husarion_ugv_hardware_interfaces/README.md similarity index 97% rename from panther_hardware_interfaces/README.md rename to husarion_ugv_hardware_interfaces/README.md index 545dd7778..9908e4e70 100644 --- a/panther_hardware_interfaces/README.md +++ b/husarion_ugv_hardware_interfaces/README.md @@ -1,4 +1,4 @@ -# panther_hardware_interfaces +# husarion_ugv_hardware_interfaces Package that implements SystemInterface from ros2_control for Panther. @@ -66,7 +66,7 @@ LynxSystem additional CAN settings > [!CAUTION] > `max_write_pdo_cmds_errors_count`, `max_read_pdo_motor_states_errors_count`, `max_read_pdo_driver_state_errors_count`, `sdo_operation_timeout`, `pdo_motor_states_timeout_ms` and `pdo_driver_state_timeout_ms` are safety-critical parameters, they should be changed only in very specific cases, be sure that you know how they work and be really cautious when changing them. -### PantherImuSensor +### PhidgetImuSensor Plugin responsible for communicating with IMU and filtering data using Madgwick Filter. @@ -158,8 +158,8 @@ sudo apt install -y kmod iproute2 ### Running tests ```bash -colcon build --packages-select panther_hardware_interfaces --symlink-install -colcon test --event-handlers console_direct+ --packages-select panther_hardware_interfaces --parallel-workers 1 +colcon build --packages-select husarion_ugv_hardware_interfaces --symlink-install +colcon test --event-handlers console_direct+ --packages-select husarion_ugv_hardware_interfaces --parallel-workers 1 colcon test-result --verbose --all ``` diff --git a/panther_hardware_interfaces/cmake/SuperBuild.cmake b/husarion_ugv_hardware_interfaces/cmake/SuperBuild.cmake similarity index 98% rename from panther_hardware_interfaces/cmake/SuperBuild.cmake rename to husarion_ugv_hardware_interfaces/cmake/SuperBuild.cmake index c7fca72e8..685b8d1b4 100644 --- a/panther_hardware_interfaces/cmake/SuperBuild.cmake +++ b/husarion_ugv_hardware_interfaces/cmake/SuperBuild.cmake @@ -46,7 +46,7 @@ ExternalProject_Add( BUILD_IN_SOURCE 1) ExternalProject_Add( - ep_panther_hardware_interfaces + ep_husarion_ugv_hardware_interfaces DEPENDS ${DEPENDENCIES} SOURCE_DIR ${PROJECT_SOURCE_DIR} CMAKE_ARGS -DUSE_SUPERBUILD=OFF diff --git a/panther_hardware_interfaces/config/canopen_configuration.yaml b/husarion_ugv_hardware_interfaces/config/canopen_configuration.yaml similarity index 100% rename from panther_hardware_interfaces/config/canopen_configuration.yaml rename to husarion_ugv_hardware_interfaces/config/canopen_configuration.yaml diff --git a/panther_hardware_interfaces/config/master.dcf b/husarion_ugv_hardware_interfaces/config/master.dcf similarity index 100% rename from panther_hardware_interfaces/config/master.dcf rename to husarion_ugv_hardware_interfaces/config/master.dcf diff --git a/panther_hardware_interfaces/config/phidgets_spatial_parameters.yaml b/husarion_ugv_hardware_interfaces/config/phidgets_spatial_parameters.yaml similarity index 100% rename from panther_hardware_interfaces/config/phidgets_spatial_parameters.yaml rename to husarion_ugv_hardware_interfaces/config/phidgets_spatial_parameters.yaml diff --git a/panther_hardware_interfaces/config/roboteq_motor_controllers_v80_21a.eds b/husarion_ugv_hardware_interfaces/config/roboteq_motor_controllers_v80_21a.eds similarity index 100% rename from panther_hardware_interfaces/config/roboteq_motor_controllers_v80_21a.eds rename to husarion_ugv_hardware_interfaces/config/roboteq_motor_controllers_v80_21a.eds diff --git a/panther_hardware_interfaces/panther_hardware_interfaces.xml b/husarion_ugv_hardware_interfaces/husarion_ugv_hardware_interfaces.xml similarity index 57% rename from panther_hardware_interfaces/panther_hardware_interfaces.xml rename to husarion_ugv_hardware_interfaces/husarion_ugv_hardware_interfaces.xml index dbb3512ea..7be01ed8b 100644 --- a/panther_hardware_interfaces/panther_hardware_interfaces.xml +++ b/husarion_ugv_hardware_interfaces/husarion_ugv_hardware_interfaces.xml @@ -1,22 +1,22 @@ - - + Hardware system controller for Panther's Roboteq motor controller - Hardware system controller for Panther's Roboteq motor controller - Hardware IMU sensor for Panther's Phidget Spatial Inertial Measurement Unit diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_imu_sensor/panther_imu_sensor.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/phidget_imu_sensor/phidget_imu_sensor.hpp similarity index 92% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_imu_sensor/panther_imu_sensor.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/phidget_imu_sensor/phidget_imu_sensor.hpp index 5ac14ee42..d195ca063 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_imu_sensor/panther_imu_sensor.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/phidget_imu_sensor/phidget_imu_sensor.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_IMU_SENSOR_PANTHER_IMU_SENSOR_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_IMU_SENSOR_PANTHER_IMU_SENSOR_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_PHIDGET_IMU_SENSOR_PHIDGET_IMU_SENSOR_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_PHIDGET_IMU_SENSOR_PHIDGET_IMU_SENSOR_HPP_ #include #include @@ -43,7 +43,7 @@ using namespace std::placeholders; -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { using return_type = hardware_interface::return_type; @@ -54,10 +54,10 @@ using CommandInterface = hardware_interface::CommandInterface; /** * @brief Class that implements SensorInterface from ros2_control for Panther */ -class PantherImuSensor : public hardware_interface::SensorInterface +class PhidgetImuSensor : public hardware_interface::SensorInterface { public: - RCLCPP_SHARED_PTR_DEFINITIONS(PantherImuSensor) + RCLCPP_SHARED_PTR_DEFINITIONS(PhidgetImuSensor) CallbackReturn on_init(const hardware_interface::HardwareInfo & hardware_info) override; CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; @@ -143,7 +143,7 @@ class PantherImuSensor : public hardware_interface::SensorInterface std::vector imu_sensor_state_; - rclcpp::Logger logger_{rclcpp::get_logger("PantherImuSensor")}; + rclcpp::Logger logger_{rclcpp::get_logger("PhidgetImuSensor")}; rclcpp::Clock steady_clock_{RCL_STEADY_TIME}; inline static const std::array kImuInterfacesNames = { @@ -180,6 +180,6 @@ class PantherImuSensor : public hardware_interface::SensorInterface rclcpp::Time last_spatial_data_timestamp_; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_IMU_SENSOR_PANTHER_IMU_SENSOR_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_PHIDGET_IMU_SENSOR_PHIDGET_IMU_SENSOR_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/gpio_controller.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_controller.hpp similarity index 95% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/gpio_controller.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_controller.hpp index 53315d8fc..f563d2509 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/gpio_controller.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_controller.hpp @@ -17,8 +17,8 @@ * @brief Header file containing a higher-level wrapper for the GPIO driver. */ -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_GPIO_CONTROLLER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_GPIO_CONTROLLER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_GPIO_CONTROLLER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_GPIO_CONTROLLER_HPP_ #include #include @@ -29,12 +29,12 @@ #include "gpiod.hpp" -#include "panther_utils/common_utilities.hpp" +#include "husarion_ugv_utils/common_utilities.hpp" -#include "panther_hardware_interfaces/panther_system/gpio/gpio_driver.hpp" -#include "panther_hardware_interfaces/panther_system/gpio/types.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_driver.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/gpio/types.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { class EStopResetInterrupted : public std::exception @@ -403,7 +403,7 @@ class GPIOControllerFactory { std::unique_ptr gpio_controller; - if (panther_utils::common_utilities::MeetsVersionRequirement(robot_version, 1.2)) { + if (husarion_ugv_utils::common_utilities::MeetsVersionRequirement(robot_version, 1.2)) { auto config_info_storage = GPIOControllerPTH12X::GetGPIOConfigInfoStorage(); auto gpio_driver = std::make_shared(config_info_storage); @@ -419,6 +419,6 @@ class GPIOControllerFactory }; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_GPIO_CONTROLLER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_GPIO_CONTROLLER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/gpio_driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_driver.hpp similarity index 95% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/gpio_driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_driver.hpp index e46775fcd..a79b29f99 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/gpio_driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/gpio_driver.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_GPIO_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_GPIO_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_GPIO_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_GPIO_DRIVER_HPP_ #include #include @@ -29,9 +29,9 @@ #include "gpiod.hpp" -#include "panther_hardware_interfaces/panther_system/gpio/types.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/gpio/types.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { class GPIODriverInterface @@ -247,6 +247,6 @@ class GPIODriver : public GPIODriverInterface const std::filesystem::path gpio_chip_path_ = "/dev/gpiochip0"; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_GPIO_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_GPIO_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/types.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/types.hpp similarity index 87% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/types.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/types.hpp index 9695a8fd2..987380ba7 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/gpio/types.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/gpio/types.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_TYPES_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_TYPES_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_TYPES_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_TYPES_HPP_ #include #include #include "gpiod.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { /** @@ -83,6 +83,6 @@ struct GPIOInfo gpiod::line::offset offset = -1; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_GPIO_TYPES_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_GPIO_TYPES_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/lynx_system.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/lynx_system.hpp similarity index 80% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/lynx_system.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/lynx_system.hpp index b5927e59f..40a61823a 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/lynx_system.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/lynx_system.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_LYNX_SYSTEM_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_LYNX_SYSTEM_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_LYNX_SYSTEM_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_LYNX_SYSTEM_HPP_ #include #include -#include "panther_hardware_interfaces/panther_system/ugv_system.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/ugv_system.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { /** @@ -55,6 +55,6 @@ class LynxSystem : public UGVSystem static const inline std::vector kJointOrder = {"fl", "fr", "rl", "rr"}; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_LYNX_SYSTEM_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_LYNX_SYSTEM_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/panther_system.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/panther_system.hpp similarity index 80% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/panther_system.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/panther_system.hpp index 80cf06bb7..4fcee2b79 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/panther_system.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/panther_system.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_PANTHER_SYSTEM_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_PANTHER_SYSTEM_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_SYSTEM_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_SYSTEM_HPP_ #include #include -#include "panther_hardware_interfaces/panther_system/ugv_system.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/ugv_system.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { /** @@ -55,6 +55,6 @@ class PantherSystem : public UGVSystem static const inline std::vector kJointOrder = {"fl", "fr", "rl", "rr"}; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_PANTHER_SYSTEM_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_SYSTEM_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/canopen_manager.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/canopen_manager.hpp similarity index 91% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/canopen_manager.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/canopen_manager.hpp index 2c00eb69a..8ca1fbe0b 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/canopen_manager.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/canopen_manager.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_CANOPEN_MANAGER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_CANOPEN_MANAGER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_CANOPEN_MANAGER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_CANOPEN_MANAGER_HPP_ #include #include @@ -33,7 +33,7 @@ #include "lely/io2/sys/sigset.hpp" #include "lely/io2/sys/timer.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { struct CANopenObject @@ -133,6 +133,6 @@ class CANopenManager const CANopenSettings canopen_settings_; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_CANOPEN_MANAGER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_CANOPEN_MANAGER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/driver.hpp similarity index 91% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/driver.hpp index e4cc87c58..760cfde5a 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/driver.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_DRIVER_HPP_ #include #include @@ -25,7 +25,7 @@ #include "lely/coapp/loop_driver.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { struct MotorDriverState @@ -145,6 +145,6 @@ class DriverInterface using SharedPtr = std::shared_ptr; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/lynx_robot_driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/lynx_robot_driver.hpp similarity index 76% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/lynx_robot_driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/lynx_robot_driver.hpp index 25b611140..4991373a8 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/lynx_robot_driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/lynx_robot_driver.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_LYNX_ROBOT_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_LYNX_ROBOT_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_LYNX_ROBOT_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_LYNX_ROBOT_DRIVER_HPP_ #include #include #include -#include "panther_hardware_interfaces/panther_system/robot_driver/canopen_manager.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_data_converters.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_robot_driver.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/canopen_manager.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_robot_driver.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { /** @@ -66,6 +66,6 @@ class LynxRobotDriver : public RoboteqRobotDriver void DefineDrivers() override; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_LYNX_ROBOT_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_LYNX_ROBOT_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/panther_robot_driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/panther_robot_driver.hpp similarity index 77% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/panther_robot_driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/panther_robot_driver.hpp index 40665e76b..d72d36f20 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/panther_robot_driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/panther_robot_driver.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_PANTHER_ROBOT_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_PANTHER_ROBOT_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_PANTHER_ROBOT_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_PANTHER_ROBOT_DRIVER_HPP_ #include #include #include -#include "panther_hardware_interfaces/panther_system/robot_driver/canopen_manager.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_data_converters.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_robot_driver.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/canopen_manager.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_robot_driver.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { /** @@ -68,6 +68,6 @@ class PantherRobotDriver : public RoboteqRobotDriver virtual void DefineDrivers(); }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_PANTHER_ROBOT_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_PANTHER_ROBOT_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/robot_driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/robot_driver.hpp similarity index 87% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/robot_driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/robot_driver.hpp index 78e38064b..177e61421 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/robot_driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/robot_driver.hpp @@ -12,15 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOT_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOT_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOT_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOT_DRIVER_HPP_ #include #include -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_data_converters.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { /** @@ -116,6 +116,6 @@ class RobotDriverInterface virtual bool CommunicationError() = 0; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOT_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOT_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_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 similarity index 93% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_data_converters.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp index afc071e43..ba3649db7 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_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 @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DATA_CONVERTERS_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DATA_CONVERTERS_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DATA_CONVERTERS_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DATA_CONVERTERS_HPP_ #include #include @@ -25,10 +25,10 @@ #include "panther_msgs/msg/runtime_error.hpp" #include "panther_msgs/msg/script_flag.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_driver.hpp" -#include "panther_hardware_interfaces/utils.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp" +#include "husarion_ugv_hardware_interfaces/utils.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { struct DrivetrainSettings @@ -258,6 +258,6 @@ class DriverData bool heartbeat_timeout_ = false; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DATA_CONVERTERS_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DATA_CONVERTERS_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp similarity index 93% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp index a499120aa..729339ab7 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DRIVER_HPP_ #include #include @@ -25,9 +25,9 @@ #include "lely/coapp/loop_driver.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/driver.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/driver.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { // Forward declaration @@ -195,6 +195,6 @@ class RoboteqMotorDriver : public MotorDriverInterface const std::uint8_t channel_; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_error_filter.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_error_filter.hpp similarity index 90% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_error_filter.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_error_filter.hpp index 53a13d10b..063df2da8 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_error_filter.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_error_filter.hpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ERROR_FILTER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ERROR_FILTER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ERROR_FILTER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ERROR_FILTER_HPP_ #include #include #include -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { class ErrorFilter @@ -102,6 +102,6 @@ class RoboteqErrorFilter std::map error_filters_; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ERROR_FILTER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ERROR_FILTER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_robot_driver.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_robot_driver.hpp similarity index 87% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_robot_driver.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_robot_driver.hpp index 6f8723078..ea088a567 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/robot_driver/roboteq_robot_driver.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_robot_driver.hpp @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ROBOT_DRIVER_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ROBOT_DRIVER_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ROBOT_DRIVER_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ROBOT_DRIVER_HPP_ #include #include #include -#include "panther_hardware_interfaces/panther_system/robot_driver/canopen_manager.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/robot_driver.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_data_converters.hpp" -#include "panther_hardware_interfaces/panther_system/robot_driver/roboteq_driver.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/canopen_manager.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/robot_driver.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_data_converters.hpp" +#include "husarion_ugv_hardware_interfaces/robot_system/robot_driver/roboteq_driver.hpp" -namespace panther_hardware_interfaces +namespace husarion_ugv_hardware_interfaces { struct MotorNames @@ -170,6 +170,6 @@ class RoboteqRobotDriver : public RobotDriverInterface const std::chrono::milliseconds activate_wait_time_; }; -} // namespace panther_hardware_interfaces +} // namespace husarion_ugv_hardware_interfaces -#endif // PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ROBOT_DRIVER_HPP_ +#endif // HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_ROBOT_DRIVER_ROBOTEQ_ROBOT_DRIVER_HPP_ diff --git a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/system_e_stop.hpp b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_e_stop.hpp similarity index 87% rename from panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/system_e_stop.hpp rename to husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_e_stop.hpp index a0d1088eb..7cc903a36 100644 --- a/panther_hardware_interfaces/include/panther_hardware_interfaces/panther_system/system_e_stop.hpp +++ b/husarion_ugv_hardware_interfaces/include/husarion_ugv_hardware_interfaces/robot_system/system_e_stop.hpp @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_SYSTEM_E_STOP_HPP_ -#define PANTHER_HARDWARE_INTERFACES_PANTHER_SYSTEM_SYSTEM_E_STOP_HPP_ +#ifndef HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_SYSTEM_E_STOP_HPP_ +#define HUSARION_UGV_HARDWARE_INTERFACES_ROBOT_SYSTEM_SYSTEM_E_STOP_HPP_ #include #include #include