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
80 rclcpp_lifecycle::State(
81 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
82 sensor_logger_(rclcpp::get_logger(
"sensor_interface"))
106 [[deprecated(
"Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
108 const HardwareInfo & hardware_info, rclcpp::Logger logger,
109 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
111 return this->
init(hardware_info, logger, clock_interface->get_clock());
124 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
126 sensor_clock_ = clock;
127 sensor_logger_ = logger.get_child(
"hardware_component.sensor." + hardware_info.
name);
128 info_ = hardware_info;
133 read_async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
134 read_async_handler_->init(
137 read_async_handler_->start_thread();
150 info_ = hardware_info;
153 return CallbackReturn::SUCCESS;
169 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
170 "Exporting is handled "
171 "by the Framework.")]]
virtual std::vector<StateInterface>
186 virtual std::vector<hardware_interface::InterfaceDescription>
203 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
206 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
207 state_interfaces.reserve(
208 unlisted_interface_descriptions.size() + sensor_state_interfaces_.size() +
209 joint_state_interfaces_.size());
212 for (
const auto & description : unlisted_interface_descriptions)
214 auto name = description.get_name();
215 unlisted_state_interfaces_.insert(std::make_pair(name, description));
216 auto state_interface = std::make_shared<StateInterface>(description);
217 sensor_states_map_.insert(std::make_pair(name, state_interface));
218 unlisted_states_.push_back(state_interface);
219 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
222 for (
const auto & [name, descr] : sensor_state_interfaces_)
225 auto state_interface = std::make_shared<StateInterface>(descr);
226 sensor_states_map_.insert(std::make_pair(name, state_interface));
227 sensor_states_.push_back(state_interface);
228 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
231 for (
const auto & [name, descr] : joint_state_interfaces_)
233 auto state_interface = std::make_shared<StateInterface>(descr);
234 sensor_states_map_.insert(std::make_pair(name, state_interface));
235 joint_states_.push_back(state_interface);
236 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
239 return state_interfaces;
253 const rclcpp::Time & time,
const rclcpp::Duration & period)
256 status.result = return_type::ERROR;
259 const auto result = read_async_handler_->trigger_async_callback(time, period);
260 status.successful = result.first;
261 status.result = result.second;
262 const auto execution_time = read_async_handler_->get_last_execution_time();
263 if (execution_time.count() > 0)
265 status.execution_time = execution_time;
267 if (!status.successful)
271 "Trigger read called while read async handler is still in progress for hardware "
272 "interface : '%s'. Failed to trigger read cycle!",
274 status.result = return_type::OK;
280 const auto start_time = std::chrono::steady_clock::now();
281 status.successful =
true;
282 status.result =
read(time, period);
283 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
284 std::chrono::steady_clock::now() - start_time);
299 virtual return_type
read(
const rclcpp::Time & time,
const rclcpp::Duration & period) = 0;
325 lifecycle_state_ = new_state;
328 template <
typename T>
329 void set_state(
const std::string & interface_name,
const T & value)
331 auto it = sensor_states_map_.find(interface_name);
332 if (it == sensor_states_map_.end())
334 throw std::runtime_error(
335 "State interface not found: " + interface_name +
336 " in sensor hardware component: " + info_.
name +
". This should not happen.");
338 auto & handle = it->second;
339 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
340 std::ignore = handle->set_value(lock, value);
343 template <
typename T =
double>
344 T get_state(
const std::string & interface_name)
const
346 auto it = sensor_states_map_.find(interface_name);
347 if (it == sensor_states_map_.end())
349 throw std::runtime_error(
350 "State interface not found: " + interface_name +
351 " in sensor hardware component: " + info_.
name +
". This should not happen.");
353 auto & handle = it->second;
354 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
355 const auto opt_value = handle->get_optional<T>(lock);
358 throw std::runtime_error(
359 "Failed to get state value from interface: " + interface_name +
360 ". This should not happen.");
362 return opt_value.value();
375 rclcpp::Clock::SharedPtr
get_clock()
const {
return sensor_clock_; }
391 stats_registrations_.enableAll();
395 stats_registrations_.disableAll();
402 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
403 std::unordered_map<std::string, InterfaceDescription> sensor_state_interfaces_;
404 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
407 std::vector<StateInterface::SharedPtr> joint_states_;
408 std::vector<StateInterface::SharedPtr> sensor_states_;
409 std::vector<StateInterface::SharedPtr> unlisted_states_;
411 rclcpp_lifecycle::State lifecycle_state_;
412 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> read_async_handler_;
415 rclcpp::Clock::SharedPtr sensor_clock_;
416 rclcpp::Logger sensor_logger_;
418 std::unordered_map<std::string, StateInterface::SharedPtr> sensor_states_map_;
421 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:172
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the SensorInterface.
Definition sensor_interface.hpp:375
const HardwareInfo & get_hardware_info() const
Get the hardware info of the SensorInterface.
Definition sensor_interface.hpp:381
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition sensor_interface.hpp:311
rclcpp::Logger get_logger() const
Get the logger of the SensorInterface.
Definition sensor_interface.hpp:369
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:200
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:148
const std::string & get_name() const
Get name of the actuator hardware.
Definition sensor_interface.hpp:305
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:252
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition sensor_interface.hpp:187
void enable_introspection(bool enable)
Enable or disable introspection of the sensor hardware.
Definition sensor_interface.hpp:387
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition sensor_interface.hpp:323
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition sensor_interface.hpp:123
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition sensor_interface.hpp:107
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition sensor_interface.hpp:317
Definition actuator.hpp:34
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1012
Definition hardware_interface_return_values.hpp:41
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:232
int thread_priority
Async thread priority.
Definition hardware_info.hpp:244
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:238
bool is_async
Component is async.
Definition hardware_info.hpp:242
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:253
std::string name
Name of the hardware.
Definition hardware_info.hpp:234
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:262