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>
30#include "hardware_interface/handle.hpp"
31#include "hardware_interface/hardware_info.hpp"
32#include "hardware_interface/sensor_interface.hpp"
33#include "hardware_interface/system_interface.hpp"
34#include "hardware_interface/types/hardware_interface_return_values.hpp"
35#include "rclcpp/clock.hpp"
36#include "rclcpp/logger.hpp"
37#include "rclcpp/macros.hpp"
38#include "rclcpp/time.hpp"
39#include "realtime_tools/realtime_buffer.hpp"
41namespace ros2_control_demo_example_14
48 hardware_interface::CallbackReturn
on_init(
53 hardware_interface::CallbackReturn on_configure(
54 const rclcpp_lifecycle::State & previous_state)
override;
56 hardware_interface::CallbackReturn on_activate(
57 const rclcpp_lifecycle::State & previous_state)
override;
59 hardware_interface::CallbackReturn on_deactivate(
60 const rclcpp_lifecycle::State & previous_state)
override;
62 hardware_interface::CallbackReturn on_cleanup(
63 const rclcpp_lifecycle::State & previous_state)
override;
65 hardware_interface::CallbackReturn on_shutdown(
66 const rclcpp_lifecycle::State & previous_state)
override;
68 hardware_interface::return_type
read(
69 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
81 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_; }
90 std::shared_ptr<rclcpp::Logger> logger_;
91 rclcpp::Clock::SharedPtr clock_;
94 double measured_velocity;
95 double last_measured_velocity_;
96 double hw_joint_state_;
99 rclcpp::Time last_timestamp_;
100 rclcpp::Time current_timestamp;
104 std::atomic<bool> receive_data_;
107 std::thread incoming_data_thread_;
109 std::condition_variable cv;
112 struct sockaddr_in address_;
Virtual Class to implement when integrating a stand-alone sensor into ros2_control.
Definition sensor_interface.hpp:68
Definition rrbot_sensor_for_position_feedback.hpp:44
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:280
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition rrbot_sensor_for_position_feedback.cpp:216
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SensorInterface.
Definition rrbot_sensor_for_position_feedback.hpp:81
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::Logger get_logger() const
Get the logger of the SensorInterface.
Definition rrbot_sensor_for_position_feedback.hpp:75
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:106