ros2_control - humble
rrbot_sensor_for_position_feedback.hpp
1 // Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
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 //
16 // Authors: Denis Stogl
17 //
18 
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_
21 
22 #include <netinet/in.h>
23 #include <memory>
24 #include <string>
25 #include <thread>
26 #include <vector>
27 
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/logger.hpp"
35 #include "rclcpp/macros.hpp"
36 #include "rclcpp/time.hpp"
37 #include "realtime_tools/realtime_buffer.hpp"
38 
39 namespace ros2_control_demo_example_14
40 {
42 {
43 public:
44  RCLCPP_SHARED_PTR_DEFINITIONS(RRBotSensorPositionFeedback);
45 
47  const hardware_interface::HardwareInfo & info) override;
48 
49  std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
50 
52  const rclcpp_lifecycle::State & previous_state) override;
53 
55  const rclcpp_lifecycle::State & previous_state) override;
56 
58  const rclcpp_lifecycle::State & previous_state) override;
59 
61  const rclcpp_lifecycle::State & previous_state) override;
62 
63  hardware_interface::return_type read(
64  const rclcpp::Time & time, const rclcpp::Duration & period) override;
65 
67 
70  rclcpp::Logger get_logger() const { return *logger_; }
71 
73 
76  rclcpp::Clock::SharedPtr get_clock() const { return clock_; }
77 
78 private:
79  // Parameters for the RRBot simulation
80  double hw_start_sec_;
81  double hw_stop_sec_;
82  double hw_slowdown_;
83 
84  // Objects for logging
85  std::shared_ptr<rclcpp::Logger> logger_;
86  rclcpp::Clock::SharedPtr clock_;
87 
88  // Store the command for the simulated robot
89  double measured_velocity; // Local variable, but avoid initialization on each read
90  double last_measured_velocity_;
91  double hw_joint_state_;
92 
93  // Timestamps to calculate position for velocity
94  rclcpp::Time last_timestamp_;
95  rclcpp::Time current_timestamp; // Local variable, but avoid initialization on each read
96 
97  // Sync incoming commands between threads
98  realtime_tools::RealtimeBuffer<double> rt_incomming_data_ptr_;
99 
100  // Create timer to checking incoming data on socket
101  std::thread incoming_data_thread_;
102 
103  // Fake "mechanical connection" between actuator and sensor using sockets
104  struct sockaddr_in address_;
105  int socket_port_;
106  int address_length_;
107  int obj_socket_;
108  int sockoptval_ = 1;
109  int sock_;
110 };
111 
112 } // namespace ros2_control_demo_example_14
113 
114 #endif // ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_SENSOR_FOR_POSITION_FEEDBACK_HPP_
Definition: sensor_interface.hpp:72
Definition: rrbot_sensor_for_position_feedback.hpp:42
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:249
std::vector< hardware_interface::StateInterface > export_state_interfaces() override
Exports all state interfaces for this hardware interface.
Definition: rrbot_sensor_for_position_feedback.cpp:186
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SensorInterface.
Definition: rrbot_sensor_for_position_feedback.hpp:76
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:70
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturn
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition: actuator_interface.hpp:69
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:106