ros2_control - rolling
Loading...
Searching...
No Matches
cm_topic_hardware_component.hpp
1// Copyright 2025 AIT Austrian Institute of Technology GmbH
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/* Author: Christoph Froehlich */
16
17#pragma once
18
19// C++
20#include <memory>
21#include <string>
22
23// ROS
24#include <hardware_interface/system_interface.hpp>
25#include <hardware_interface/types/hardware_component_interface_params.hpp>
26#include <rclcpp/subscription.hpp>
27
28#include <pal_statistics_msgs/msg/statistics_names.hpp>
29#include <pal_statistics_msgs/msg/statistics_values.hpp>
30
31namespace cm_topic_hardware_component
32{
33using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
34
36{
37public:
38 CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams& params) override;
39
40 hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
41
42 hardware_interface::return_type write(const rclcpp::Time& /*time*/, const rclcpp::Duration& /*period*/) override;
43
44private:
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_;
49};
50
51} // namespace cm_topic_hardware_component
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 &params) 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