24#include <hardware_interface/system_interface.hpp>
25#include <hardware_interface/types/hardware_component_interface_params.hpp>
26#include <rclcpp/subscription.hpp>
28#include <pal_statistics_msgs/msg/statistics_names.hpp>
29#include <pal_statistics_msgs/msg/statistics_values.hpp>
31namespace cm_topic_hardware_component
33using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
40 hardware_interface::return_type
read(
const rclcpp::Time& time,
const rclcpp::Duration& period)
override;
42 hardware_interface::return_type
write(
const rclcpp::Time& ,
const rclcpp::Duration& )
override;
45 rclcpp::Subscription<pal_statistics_msgs::msg::StatisticsNames>::SharedPtr pal_names_subscriber_;
46 rclcpp::Subscription<pal_statistics_msgs::msg::StatisticsValues>::SharedPtr pal_values_subscriber_;
47 pal_statistics_msgs::msg::StatisticsValues latest_pal_values_;
48 std::unordered_map<uint32_t, std::vector<std::string>> pal_statistics_names_per_topic_;
Definition cm_topic_hardware_component.hpp:36
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the hardware.
Definition cm_topic_hardware_component.cpp:44
CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams ¶ms) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition cm_topic_hardware_component.cpp:24
hardware_interface::return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the hardware.
Definition cm_topic_hardware_component.cpp:79
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:67
Parameters required for the initialization of a specific hardware component plugin....
Definition hardware_component_interface_params.hpp:32