15#ifndef HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__SENSOR_INTERFACE_HPP_
21#include <unordered_map>
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"
43using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
75class SensorInterface :
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
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"))
106 const HardwareInfo & hardware_info, rclcpp::Logger logger,
107 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
109 clock_interface_ = clock_interface;
110 sensor_logger_ = logger.get_child(
"hardware_component.sensor." + hardware_info.
name);
111 info_ = hardware_info;
116 read_async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
117 read_async_handler_->init(
120 read_async_handler_->start_thread();
133 info_ = hardware_info;
136 return CallbackReturn::SUCCESS;
152 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
153 "Exporting is handled "
154 "by the Framework.")]]
virtual std::vector<StateInterface>
169 virtual std::vector<hardware_interface::InterfaceDescription>
186 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
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());
195 for (
const auto & description : unlisted_interface_descriptions)
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));
205 for (
const auto & [name, descr] : sensor_state_interfaces_)
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));
214 for (
const auto & [name, descr] : joint_state_interfaces_)
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));
222 return state_interfaces;
236 const rclcpp::Time & time,
const rclcpp::Duration & period)
239 status.result = return_type::ERROR;
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)
248 status.execution_time = execution_time;
250 if (!status.successful)
254 "Trigger read called while read async handler is still in progress for hardware "
255 "interface : '%s'. Failed to trigger read cycle!",
257 status.result = return_type::OK;
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);
282 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
308 lifecycle_state_ = new_state;
311 void set_state(
const std::string & interface_name,
const double & value)
313 sensor_states_map_.at(interface_name)->set_value(value);
316 double get_state(
const std::string & interface_name)
const
318 return sensor_states_map_.at(interface_name)->get_value();
331 rclcpp::Clock::SharedPtr
get_clock()
const {
return clock_interface_->get_clock(); }
347 stats_registrations_.enableAll();
351 stats_registrations_.disableAll();
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_;
363 std::vector<StateInterface::SharedPtr> joint_states_;
364 std::vector<StateInterface::SharedPtr> sensor_states_;
365 std::vector<StateInterface::SharedPtr> unlisted_states_;
367 rclcpp_lifecycle::State lifecycle_state_;
368 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> read_async_handler_;
371 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
372 rclcpp::Logger sensor_logger_;
374 std::unordered_map<std::string, StateInterface::SharedPtr> sensor_states_map_;
377 pal_statistics::RegistrationsRAII stats_registrations_;
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