19 #ifndef ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_SENSOR_FOR_POSITION_FEEDBACK_HPP_
20 #define ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_SENSOR_FOR_POSITION_FEEDBACK_HPP_
22 #include <netinet/in.h>
28 #include "hardware_interface/handle.hpp"
29 #include "hardware_interface/hardware_info.hpp"
30 #include "hardware_interface/sensor_interface.hpp"
31 #include "hardware_interface/system_interface.hpp"
32 #include "hardware_interface/types/hardware_interface_return_values.hpp"
33 #include "rclcpp/clock.hpp"
34 #include "rclcpp/macros.hpp"
35 #include "rclcpp/time.hpp"
36 #include "realtime_tools/realtime_buffer.h"
38 namespace ros2_control_demo_example_14
51 const rclcpp_lifecycle::State & previous_state)
override;
54 const rclcpp_lifecycle::State & previous_state)
override;
57 const rclcpp_lifecycle::State & previous_state)
override;
60 const rclcpp_lifecycle::State & previous_state)
override;
62 hardware_interface::return_type
read(
63 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
72 double measured_velocity;
73 double last_measured_velocity_;
74 double hw_joint_state_;
78 rclcpp::Time last_timestamp_;
79 rclcpp::Time current_timestamp;
85 std::thread incoming_data_thread_;
88 struct sockaddr_in address_;
Definition: sensor_interface.hpp:79
Definition: rrbot_sensor_for_position_feedback.hpp:41
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Read the current state values from the actuator.
Definition: rrbot_sensor_for_position_feedback.cpp:246
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition: rrbot_sensor_for_position_feedback.cpp:183
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition: rrbot_sensor_for_position_feedback.cpp:40
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:76
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:170