ros2_control - rolling
Loading...
Searching...
No Matches
sensor_interface.hpp
1// Copyright 2020 - 2021 ros2_control Development Team
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#ifndef HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
17
18#include <limits>
19#include <memory>
20#include <string>
21#include <unordered_map>
22#include <utility>
23#include <vector>
24
25#include "hardware_interface/component_parser.hpp"
26#include "hardware_interface/handle.hpp"
27#include "hardware_interface/hardware_info.hpp"
28#include "hardware_interface/introspection.hpp"
29#include "hardware_interface/types/hardware_interface_return_values.hpp"
30#include "hardware_interface/types/lifecycle_state_names.hpp"
31#include "lifecycle_msgs/msg/state.hpp"
32#include "rclcpp/duration.hpp"
33#include "rclcpp/logger.hpp"
34#include "rclcpp/node_interfaces/node_clock_interface.hpp"
35#include "rclcpp/time.hpp"
36#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
37#include "rclcpp_lifecycle/state.hpp"
38#include "realtime_tools/async_function_handler.hpp"
39
40namespace hardware_interface
41{
42
43using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
44
46
75class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
76{
77public:
79 : lifecycle_state_(rclcpp_lifecycle::State(
80 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
81 sensor_logger_(rclcpp::get_logger("sensor_interface"))
82 {
83 }
84
86
90 SensorInterface(const SensorInterface & other) = delete;
91
92 SensorInterface(SensorInterface && other) = delete;
93
94 virtual ~SensorInterface() = default;
95
98
105 CallbackReturn init(
106 const HardwareInfo & hardware_info, rclcpp::Logger logger,
107 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
108 {
109 clock_interface_ = clock_interface;
110 sensor_logger_ = logger.get_child("hardware_component.sensor." + hardware_info.name);
111 info_ = hardware_info;
112 if (info_.is_async)
113 {
114 RCLCPP_INFO_STREAM(
115 get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
116 read_async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
117 read_async_handler_->init(
118 std::bind(&SensorInterface::read, this, std::placeholders::_1, std::placeholders::_2),
119 info_.thread_priority);
120 read_async_handler_->start_thread();
121 }
122 return on_init(hardware_info);
123 };
124
126
131 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
132 {
133 info_ = hardware_info;
134 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
135 parse_state_interface_descriptions(info_.sensors, sensor_state_interfaces_);
136 return CallbackReturn::SUCCESS;
137 };
138
140
151 [[deprecated(
152 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
153 "Exporting is handled "
154 "by the Framework.")]] virtual std::vector<StateInterface>
156 {
157 // return empty vector by default. For backward compatibility we try calling
158 // export_state_interfaces() and only when empty vector is returned call
159 // on_export_state_interfaces()
160 return {};
161 }
162
169 virtual std::vector<hardware_interface::InterfaceDescription>
171 {
172 // return empty vector by default.
173 return {};
174 }
175
183 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
184 {
185 // import the unlisted interfaces
186 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
188
189 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
190 state_interfaces.reserve(
191 unlisted_interface_descriptions.size() + sensor_state_interfaces_.size() +
192 joint_state_interfaces_.size());
193
194 // add InterfaceDescriptions and create StateInterfaces from the descriptions and add to maps.
195 for (const auto & description : unlisted_interface_descriptions)
196 {
197 auto name = description.get_name();
198 unlisted_state_interfaces_.insert(std::make_pair(name, description));
199 auto state_interface = std::make_shared<StateInterface>(description);
200 sensor_states_map_.insert(std::make_pair(name, state_interface));
201 unlisted_states_.push_back(state_interface);
202 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
203 }
204
205 for (const auto & [name, descr] : sensor_state_interfaces_)
206 {
207 // TODO(Manuel) check for duplicates otherwise only the first appearance of "name" is inserted
208 auto state_interface = std::make_shared<StateInterface>(descr);
209 sensor_states_map_.insert(std::make_pair(name, state_interface));
210 sensor_states_.push_back(state_interface);
211 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
212 }
213
214 for (const auto & [name, descr] : joint_state_interfaces_)
215 {
216 auto state_interface = std::make_shared<StateInterface>(descr);
217 sensor_states_map_.insert(std::make_pair(name, state_interface));
218 joint_states_.push_back(state_interface);
219 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
220 }
221
222 return state_interfaces;
223 }
224
226
236 const rclcpp::Time & time, const rclcpp::Duration & period)
237 {
239 status.result = return_type::ERROR;
240 if (info_.is_async)
241 {
242 const auto result = read_async_handler_->trigger_async_callback(time, period);
243 status.successful = result.first;
244 status.result = result.second;
245 const auto execution_time = read_async_handler_->get_last_execution_time();
246 if (execution_time.count() > 0)
247 {
248 status.execution_time = execution_time;
249 }
250 if (!status.successful)
251 {
252 RCLCPP_WARN(
253 get_logger(),
254 "Trigger read called while read async handler is still in progress for hardware "
255 "interface : '%s'. Failed to trigger read cycle!",
256 info_.name.c_str());
257 status.result = return_type::OK;
258 return status;
259 }
260 }
261 else
262 {
263 const auto start_time = std::chrono::steady_clock::now();
264 status.successful = true;
265 status.result = read(time, period);
266 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
267 std::chrono::steady_clock::now() - start_time);
268 }
269 return status;
270 }
271
273
282 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
283
285
288 const std::string & get_name() const { return info_.name; }
289
291
294 const std::string & get_group_name() const { return info_.group; }
295
297
300 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
301
303
306 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
307 {
308 lifecycle_state_ = new_state;
309 }
310
311 void set_state(const std::string & interface_name, const double & value)
312 {
313 sensor_states_map_.at(interface_name)->set_value(value);
314 }
315
316 double get_state(const std::string & interface_name) const
317 {
318 return sensor_states_map_.at(interface_name)->get_value();
319 }
320
322
325 rclcpp::Logger get_logger() const { return sensor_logger_; }
326
328
331 rclcpp::Clock::SharedPtr get_clock() const { return clock_interface_->get_clock(); }
332
334
337 const HardwareInfo & get_hardware_info() const { return info_; }
338
340
343 void enable_introspection(bool enable)
344 {
345 if (enable)
346 {
347 stats_registrations_.enableAll();
348 }
349 else
350 {
351 stats_registrations_.disableAll();
352 }
353 }
354
355protected:
356 HardwareInfo info_;
357 // interface names to InterfaceDescription
358 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
359 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
360 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
361
362 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
363 std::vector<StateInterface::SharedPtr> joint_states_;
364 std::vector<StateInterface::SharedPtr> sensor_states_;
365 std::vector<StateInterface::SharedPtr> unlisted_states_;
366
367 rclcpp_lifecycle::State lifecycle_state_;
368 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> read_async_handler_;
369
370private:
371 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
372 rclcpp::Logger sensor_logger_;
373 // interface names to Handle accessed through getters/setters
374 std::unordered_map<std::string, StateInterface::SharedPtr> sensor_states_map_;
375
376protected:
377 pal_statistics::RegistrationsRAII stats_registrations_;
378};
379
380} // namespace hardware_interface
381#endif // HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
Virtual Class to implement when integrating a stand-alone sensor into ros2_control.
Definition sensor_interface.hpp:76
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition sensor_interface.hpp:155
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SensorInterface.
Definition sensor_interface.hpp:331
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SensorInterface.
Definition sensor_interface.hpp:337
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition sensor_interface.hpp:294
rclcpp::Logger get_logger() const
Get the logger of the SensorInterface.
Definition sensor_interface.hpp:325
SensorInterface(const SensorInterface &other)=delete
SensorInterface copy constructor is actively deleted.
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition sensor_interface.hpp:183
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition sensor_interface.hpp:131
const std::string & get_name() const
Get name of the actuator hardware.
Definition sensor_interface.hpp:288
HardwareComponentCycleStatus trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition sensor_interface.hpp:235
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition sensor_interface.hpp:170
void enable_introspection(bool enable)
Enable or disable introspection of the sensor hardware.
Definition sensor_interface.hpp:343
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition sensor_interface.hpp:306
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition sensor_interface.hpp:105
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition sensor_interface.hpp:300
Definition actuator.hpp:33
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1003
Definition hardware_interface_return_values.hpp:41
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:170
int thread_priority
Async thread priority.
Definition hardware_info.hpp:182
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:176
bool is_async
Component is async.
Definition hardware_info.hpp:180
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:191
std::string name
Name of the hardware.
Definition hardware_info.hpp:172
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:200