Skip to content

Commit

Permalink
husarion_ugv_msg -> husarion_ugv_msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Dec 11, 2024
1 parent d501fb7 commit d408f44
Show file tree
Hide file tree
Showing 73 changed files with 194 additions and 193 deletions.
12 changes: 6 additions & 6 deletions ROS_API.md
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ Below is information about the physical robot API. For the simulation, topics an
| 🤖 | 🖥️ | Topic | Description |
| --- | --- | ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
||| `battery/battery_status` | Mean values of both batteries will be published if the robot has two batteries. Otherwise, the state of the single battery will be published.<br/> [*sensor_msgs/BatteryState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/BatteryState.html) |
||| `battery/charging_status` | Battery charging status value.<br/> [*husarion_ugv_msg/ChargingStatus*](https://github.com/husarion/husarion_ugv_msg) |
||| `battery/charging_status` | Battery charging status value.<br/> [*husarion_ugv_msgs/ChargingStatus*](https://github.com/husarion/husarion_ugv_msgs) |
||| `cmd_vel` | Command velocity value.<br/> [*geometry_msgs/Twist*](https://docs.ros2.org/latest/api/geometry_msgs/msg/Twist.html) |
||| `diagnostics` | Diagnostic data.<br/> [*diagnostic_msgs/DiagnosticArray*](https://docs.ros2.org/latest/api/diagnostic_msgs/msg/DiagnosticArray.html) |
||| `dynamic_joint_states` | Information about the state of various movable joints in a robotic system.<br/> [*control_msgs/DynamicJointState*](https://github.com/ros-controls/control_msgs/blob/master/control_msgs/msg/DynamicJointState.msg) |
Expand All @@ -77,8 +77,8 @@ Below is information about the physical robot API. For the simulation, topics an
||| `gps/time_reference` | The timestamp from the GPS device.<br/> [*sensor_msgs/TimeReference*](https://docs.ros2.org/latest/api/sensor_msgs/msg/TimeReference.html) |
||| `gps/vel` | Velocity output from the GPS device.<br/> [*geometry_msgs/TwistStamped*](https://docs.ros2.org/latest/api/geometry_msgs/msg/TwistStamped.html) |
||| `hardware/e_stop` | Current E-stop state.<br/> [*std_msgs/Bool*](https://docs.ros2.org/latest/api/std_msgs/msg/Bool.html). |
||| `hardware/io_state` | Current IO state.<br/> [*husarion_ugv_msg/IOState*](https://github.com/husarion/husarion_ugv_msg) |
||| `hardware/robot_driver_state` | Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.<br/> [*husarion_ugv_msg/RobotDriverState*](https://github.com/husarion/husarion_ugv_msg) |
||| `hardware/io_state` | Current IO state.<br/> [*husarion_ugv_msgs/IOState*](https://github.com/husarion/husarion_ugv_msgs) |
||| `hardware/robot_driver_state` | Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.<br/> [*husarion_ugv_msgs/RobotDriverState*](https://github.com/husarion/husarion_ugv_msgs) |
||| `imu/data` | Filtered IMU data.<br/> [*sensor_msgs/Imu*](https://docs.ros2.org/latest/api/sensor_msgs/msg/Imu.html) |
||| `joint_states` | Provides information about the state of various joints in a robotic system.<br/> [*sensor_msgs/JointState*](https://docs.ros2.org/latest/api/sensor_msgs/msg/JointState.html) |
||| `lights/channel_1_frame` | Frame to be displayed on robot Front Bumper Lights.<br/> [*sensor_msgs/Image*](https://docs.ros2.org/latest/api/sensor_msgs/msg/Image.html) |
Expand All @@ -87,7 +87,7 @@ Below is information about the physical robot API. For the simulation, topics an
||| `odometry/filtered` | Contains information about the filtered position and orientation. When `localization_mode` is `relative`, the position and orientation are relative to the starting point. When `localization_mode` is `enu`, the orientation is relative to the east-north-up (ENU) coordinates.<br/> [*nav_msgs/Odometry*](https://docs.ros2.org/latest/api/nav_msgs/msg/Odometry.html) |
||| `odometry/wheels` | Robot odometry calculated from wheels.<br/> [*nav_msgs/Odometry*](https://docs.ros2.org/latest/api/nav_msgs/msg/Odometry.html) |
||| `robot_description` | Contains information about robot description from URDF file. <br/> [*std_msgs/String*](https://docs.ros2.org/latest/api/std_msgs/msg/String.html) |
||| `system_status` | State of the system, including Built-in Computer's CPU temperature and load. <br/> [*husarion_ugv_msg/SystemStatus*](https://github.com/husarion/husarion_ugv_msg) |
||| `system_status` | State of the system, including Built-in Computer's CPU temperature and load. <br/> [*husarion_ugv_msgs/SystemStatus*](https://github.com/husarion/husarion_ugv_msgs) |
||| `tf` | Transforms of robot system.<br/> [*tf2_msgs/TFMessage*](https://docs.ros2.org/latest/api/tf2_msgs/msg/TFMessage.html) |
||| `tf_static` | Static transforms of robot system.<br/> [*tf2_msgs/TFMessage*](https://docs.ros2.org/latest/api/tf2_msgs/msg/TFMessage.html) |

Expand Down Expand Up @@ -121,8 +121,8 @@ Below is information about the physical robot API. For the simulation, topics an
||| `hardware/e_stop_trigger` | Triggers E-stop. <br/> [std_srvs/srv/Trigger](https://docs.ros2.org/latest/api/std_srvs/srv/Trigger.html) |
||| `hardware/fan_enable` | Enables or disables fan. <br/> [std_srvs/srv/SetBool](https://docs.ros2.org/latest/api/std_srvs/srv/SetBool.html) |
||| `hardware/motor_power_enable` | Enables or disables motor power. <br/> [std_srvs/srv/SetBool](https://docs.ros2.org/latest/api/std_srvs/srv/SetBool.html) |
||| `lights/set_animation` | Sets LED animation. <br/> [husarion_ugv_msg/srv/SetLEDAnimation](https://github.com/husarion/husarion_ugv_msg) |
||| `lights/set_animation` | Sets LED animation. <br/> [husarion_ugv_msgs/srv/SetLEDAnimation](https://github.com/husarion/husarion_ugv_msgs) |
||| `localization/enable` | Enable EKF node. <br/> [std_srvs/srv/Empty](https://docs.ros2.org/latest/api/std_srvs/srv/Empty.html) |
||| `lights/set_brightness` | Sets global LED brightness, value ranges from **0.0** to **1.0**. <br/> [husarion_ugv_msg/SetLEDBrightness](https://github.com/husarion/husarion_ugv_msg) |
||| `lights/set_brightness` | Sets global LED brightness, value ranges from **0.0** to **1.0**. <br/> [husarion_ugv_msgs/SetLEDBrightness](https://github.com/husarion/husarion_ugv_msgs) |
||| `localization/set_pose` | Set pose of EKF node. <br/> [robot_localization/srv/SetPose](https://github.com/cra-ros-pkg/robot_localization/tree/ros2) |
||| `localization/toggle` | Toggle filter processing in the EKF node. <br/> [robot_localization/srv/ToggleFilterProcessing](https://github.com/cra-ros-pkg/robot_localization/tree/ros2) |
8 changes: 4 additions & 4 deletions husarion_ugv_battery/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater husarion_ugv_msg
set(PACKAGE_DEPENDENCIES ament_cmake diagnostic_updater husarion_ugv_msgs
husarion_ugv_utils rclcpp sensor_msgs)

foreach(PACKAGE IN ITEMS ${PACKAGE_DEPENDENCIES})
Expand Down Expand Up @@ -45,7 +45,7 @@ if(BUILD_TESTING)
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(${PROJECT_NAME}_test_battery rclcpp sensor_msgs
husarion_ugv_msg)
husarion_ugv_msgs)

ament_add_gtest(${PROJECT_NAME}_test_adc_battery
test/battery/test_adc_battery.cpp src/battery/adc_battery.cpp)
Expand All @@ -54,7 +54,7 @@ if(BUILD_TESTING)
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(${PROJECT_NAME}_test_adc_battery rclcpp sensor_msgs
husarion_ugv_msg)
husarion_ugv_msgs)

ament_add_gtest(
${PROJECT_NAME}_test_roboteq_battery test/battery/test_roboteq_battery.cpp
Expand All @@ -64,7 +64,7 @@ if(BUILD_TESTING)
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(${PROJECT_NAME}_test_roboteq_battery
husarion_ugv_msg rclcpp sensor_msgs)
husarion_ugv_msgs rclcpp sensor_msgs)

ament_add_gtest(
${PROJECT_NAME}_test_battery_publisher
Expand Down
6 changes: 3 additions & 3 deletions husarion_ugv_battery/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@ Publishes battery state read from ADC unit.
- `_battery/battery_1_status_raw` [*sensor_msgs/BatteryState*]: First battery raw state.
- `_battery/battery_2_status_raw` [*sensor_msgs/BatteryState*]: Second battery raw state. Published if second battery detected.
- `battery/battery_status` [*sensor_msgs/BatteryState*]: Mean values of both batteries if robot has two batteries. Otherwise, the state of the single battery will be published.
- `battery/charging_status` [*husarion_ugv_msg/ChargingStatus*]: Battery charging status.
- `battery/charging_status` [*husarion_ugv_msgs/ChargingStatus*]: Battery charging status.
- `diagnostics` [*diagnostic_msgs/DiagnosticArray*]: Battery diagnostic messages.

#### Subscribers

- `hardware/io_state` [*husarion_ugv_msg/IOState*]: Current state of IO.
- `hardware/robot_driver_state` [*husarion_ugv_msg/RobotDriverState*]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.
- `hardware/io_state` [*husarion_ugv_msgs/IOState*]: Current state of IO.
- `hardware/robot_driver_state` [*husarion_ugv_msgs/RobotDriverState*]: Current motor controllers' state and error flags. Subscribed if using Roboteq motor controllers data.

#### Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,13 @@

#include "sensor_msgs/msg/battery_state.hpp"

#include "husarion_ugv_msg/msg/charging_status.hpp"
#include "husarion_ugv_msgs/msg/charging_status.hpp"

namespace husarion_ugv_battery
{

using BatteryStateMsg = sensor_msgs::msg::BatteryState;
using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus;
using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus;

class Battery
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,17 +21,17 @@

#include "rclcpp/rclcpp.hpp"

#include "husarion_ugv_msg/msg/driver_state_named.hpp"
#include "husarion_ugv_msg/msg/robot_driver_state.hpp"
#include "husarion_ugv_msgs/msg/driver_state_named.hpp"
#include "husarion_ugv_msgs/msg/robot_driver_state.hpp"

#include "husarion_ugv_battery/battery/battery.hpp"
#include "husarion_ugv_utils/moving_average.hpp"

namespace husarion_ugv_battery
{

using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState;
using DriverStateNamedMsg = husarion_ugv_msg::msg::DriverStateNamed;
using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState;
using DriverStateNamedMsg = husarion_ugv_msgs::msg::DriverStateNamed;

struct RoboteqBatteryParams
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "diagnostic_updater/diagnostic_updater.hpp"
#include "rclcpp/rclcpp.hpp"

#include "husarion_ugv_msg/msg/robot_driver_state.hpp"
#include "husarion_ugv_msgs/msg/robot_driver_state.hpp"

#include "husarion_ugv_battery/adc_data_reader.hpp"
#include "husarion_ugv_battery/battery/battery.hpp"
Expand All @@ -30,7 +30,7 @@
namespace husarion_ugv_battery
{

using RobotDriverStateMsg = husarion_ugv_msg::msg::RobotDriverState;
using RobotDriverStateMsg = husarion_ugv_msgs::msg::RobotDriverState;

class BatteryDriverNode : public rclcpp::Node
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,15 @@

#include "sensor_msgs/msg/battery_state.hpp"

#include "husarion_ugv_msg/msg/charging_status.hpp"
#include "husarion_ugv_msg/msg/io_state.hpp"
#include "husarion_ugv_msgs/msg/charging_status.hpp"
#include "husarion_ugv_msgs/msg/io_state.hpp"

namespace husarion_ugv_battery
{

using BatteryStateMsg = sensor_msgs::msg::BatteryState;
using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus;
using IOStateMsg = husarion_ugv_msg::msg::IOState;
using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus;
using IOStateMsg = husarion_ugv_msgs::msg::IOState;

class BatteryPublisher
{
Expand Down
2 changes: 1 addition & 1 deletion husarion_ugv_battery/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>diagnostic_updater</depend>
<depend>husarion_ugv_msg</depend>
<depend>husarion_ugv_msgs</depend>
<depend>husarion_ugv_utils</depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
Expand Down
4 changes: 2 additions & 2 deletions husarion_ugv_battery/test/battery/test_adc_battery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@

#include "sensor_msgs/msg/battery_state.hpp"

#include "husarion_ugv_msg/msg/charging_status.hpp"
#include "husarion_ugv_msgs/msg/charging_status.hpp"

#include "husarion_ugv_battery/battery/adc_battery.hpp"
#include "husarion_ugv_utils/test/test_utils.hpp"

using BatteryStateMsg = sensor_msgs::msg::BatteryState;
using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus;
using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus;

class TestADCBattery : public testing::Test
{
Expand Down
4 changes: 2 additions & 2 deletions husarion_ugv_battery/test/battery/test_battery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,13 @@

#include "sensor_msgs/msg/battery_state.hpp"

#include "husarion_ugv_msg/msg/charging_status.hpp"
#include "husarion_ugv_msgs/msg/charging_status.hpp"

#include "husarion_ugv_battery/battery/battery.hpp"
#include "husarion_ugv_utils/test/test_utils.hpp"

using BatteryStateMsg = sensor_msgs::msg::BatteryState;
using ChargingStatusMsg = husarion_ugv_msg::msg::ChargingStatus;
using ChargingStatusMsg = husarion_ugv_msgs::msg::ChargingStatus;

class BatteryWrapper : public husarion_ugv_battery::Battery
{
Expand Down
Loading

0 comments on commit d408f44

Please sign in to comment.