24#include <hardware_interface/system_interface.hpp>
25#include <hardware_interface/types/hardware_component_interface_params.hpp>
26#include <rclcpp/node.hpp>
27#include <rclcpp/publisher.hpp>
28#include <rclcpp/subscription.hpp>
30#include <sensor_msgs/msg/joint_state.hpp>
32namespace joint_state_topic_hardware_interface
34using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
39 CallbackReturn on_init(
const hardware_interface::HardwareComponentInterfaceParams& params)
override;
41 hardware_interface::return_type
read(
const rclcpp::Time& time,
const rclcpp::Duration& period)
override;
43 hardware_interface::return_type
write(
const rclcpp::Time& ,
const rclcpp::Duration& )
override;
46 rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr topic_based_joint_states_subscriber_;
47 rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr topic_based_joint_commands_publisher_;
48 sensor_msgs::msg::JointState latest_joint_state_;
49 bool sum_wrapped_joint_states_{
false };
53 double trigger_joint_command_threshold_ = 1e-5;
Virtual Class to implement when integrating a complex system into ros2_control.
Definition system_interface.hpp:85
Definition joint_state_topic_hardware_interface.hpp:37
hardware_interface::return_type write(const rclcpp::Time &, const rclcpp::Duration &) override
Write the current command values to the actuator.
Definition joint_state_topic_hardware_interface.cpp:164
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition joint_state_topic_hardware_interface.cpp:89