ros2_control - humble
Loading...
Searching...
No Matches
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 <atomic>
24#include <memory>
25#include <mutex>
26#include <string>
27#include <thread>
28#include <vector>
29
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"
40
41namespace ros2_control_demo_example_14
42{
44{
45public:
46 RCLCPP_SHARED_PTR_DEFINITIONS(RRBotSensorPositionFeedback);
47
48 hardware_interface::CallbackReturn on_init(
49 const hardware_interface::HardwareInfo & info) override;
50
51 std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
52
53 hardware_interface::CallbackReturn on_configure(
54 const rclcpp_lifecycle::State & previous_state) override;
55
56 hardware_interface::CallbackReturn on_activate(
57 const rclcpp_lifecycle::State & previous_state) override;
58
59 hardware_interface::CallbackReturn on_deactivate(
60 const rclcpp_lifecycle::State & previous_state) override;
61
62 hardware_interface::CallbackReturn on_cleanup(
63 const rclcpp_lifecycle::State & previous_state) override;
64
65 hardware_interface::CallbackReturn on_shutdown(
66 const rclcpp_lifecycle::State & previous_state) override;
67
68 hardware_interface::return_type read(
69 const rclcpp::Time & time, const rclcpp::Duration & period) override;
70
72
75 rclcpp::Logger get_logger() const { return *logger_; }
76
78
81 rclcpp::Clock::SharedPtr get_clock() const { return clock_; }
82
83private:
84 // Parameters for the RRBot simulation
85 double hw_start_sec_;
86 double hw_stop_sec_;
87 double hw_slowdown_;
88
89 // Objects for logging
90 std::shared_ptr<rclcpp::Logger> logger_;
91 rclcpp::Clock::SharedPtr clock_;
92
93 // Store the command for the simulated robot
94 double measured_velocity; // Local variable, but avoid initialization on each read
95 double last_measured_velocity_;
96 double hw_joint_state_;
97
98 // Timestamps to calculate position for velocity
99 rclcpp::Time last_timestamp_;
100 rclcpp::Time current_timestamp; // Local variable, but avoid initialization on each read
101
102 // Sync incoming commands between threads
103 realtime_tools::RealtimeBuffer<double> rt_incomming_data_ptr_;
104 std::atomic<bool> receive_data_;
105
106 // Create timer to checking incoming data on socket
107 std::thread incoming_data_thread_;
108 std::mutex mtx;
109 std::condition_variable cv;
110
111 // Fake "mechanical connection" between actuator and sensor using sockets
112 struct sockaddr_in address_;
113 int socket_port_;
114 int address_length_;
115 int obj_socket_;
116 int sockoptval_ = 1;
117 int sock_;
118};
119
120} // namespace ros2_control_demo_example_14
121
122#endif // ROS2_CONTROL_DEMO_EXAMPLE_14__RRBOT_SENSOR_FOR_POSITION_FEEDBACK_HPP_
Virtual Class to implement when integrating a stand-alone sensor into ros2_control.
Definition sensor_interface.hpp:68
Definition realtime_buffer.hpp:44
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