Loading [MathJax]/extensions/tex2jax.js
ros2_control - rolling
All Classes Namespaces Functions Variables Typedefs Enumerations Pages
actuator_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__ACTUATOR_INTERFACE_HPP_
16#define HARDWARE_INTERFACE__ACTUATOR_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 "hardware_interface/types/trigger_type.hpp"
32#include "lifecycle_msgs/msg/state.hpp"
33#include "rclcpp/duration.hpp"
34#include "rclcpp/logger.hpp"
35#include "rclcpp/node_interfaces/node_clock_interface.hpp"
36#include "rclcpp/time.hpp"
37#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
38#include "rclcpp_lifecycle/state.hpp"
39#include "realtime_tools/async_function_handler.hpp"
40
41namespace hardware_interface
42{
43
44using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
45
47
91class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
92{
93public:
95 : lifecycle_state_(
96 rclcpp_lifecycle::State(
97 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
98 actuator_logger_(rclcpp::get_logger("actuator_interface"))
99 {
100 }
101
103
107 ActuatorInterface(const ActuatorInterface & other) = delete;
108
109 ActuatorInterface(ActuatorInterface && other) = delete;
110
111 virtual ~ActuatorInterface() = default;
112
115
122 [[deprecated("Use init(HardwareInfo, rclcpp::Logger, rclcpp::Clock::SharedPtr) instead.")]]
123 CallbackReturn init(
124 const HardwareInfo & hardware_info, rclcpp::Logger logger,
125 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
126 {
127 return this->init(hardware_info, logger, clock_interface->get_clock());
128 }
129
132
139 CallbackReturn init(
140 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
141 {
142 actuator_clock_ = clock;
143 actuator_logger_ = logger.get_child("hardware_component.actuator." + hardware_info.name);
144 info_ = hardware_info;
145 if (info_.is_async)
146 {
147 RCLCPP_INFO_STREAM(
148 get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
149 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
150 async_handler_->init(
151 [this](const rclcpp::Time & time, const rclcpp::Duration & period)
152 {
153 const auto read_start_time = std::chrono::steady_clock::now();
154 const auto ret_read = read(time, period);
155 const auto read_end_time = std::chrono::steady_clock::now();
156 read_return_info_.store(ret_read, std::memory_order_release);
157 read_execution_time_.store(
158 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
159 std::memory_order_release);
160 if (ret_read != return_type::OK)
161 {
162 return ret_read;
163 }
164 const auto write_start_time = std::chrono::steady_clock::now();
165 const auto ret_write = write(time, period);
166 const auto write_end_time = std::chrono::steady_clock::now();
167 write_return_info_.store(ret_write, std::memory_order_release);
168 write_execution_time_.store(
169 std::chrono::duration_cast<std::chrono::nanoseconds>(write_end_time - write_start_time),
170 std::memory_order_release);
171 return ret_write;
172 },
173 info_.thread_priority);
174 async_handler_->start_thread();
175 }
176 return on_init(hardware_info);
177 };
178
180
185 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
186 {
187 info_ = hardware_info;
188 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
189 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
190 return CallbackReturn::SUCCESS;
191 };
192
194
205 [[deprecated(
206 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
207 "Exporting is "
208 "handled "
209 "by the Framework.")]] virtual std::vector<StateInterface>
211 {
212 // return empty vector by default. For backward compatibility we try calling
213 // export_state_interfaces() and only when empty vector is returned call
214 // on_export_state_interfaces()
215 return {};
216 }
217
224 virtual std::vector<hardware_interface::InterfaceDescription>
226 {
227 // return empty vector by default.
228 return {};
229 }
230
238 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
239 {
240 // import the unlisted interfaces
241 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
243
244 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
245 state_interfaces.reserve(
246 unlisted_interface_descriptions.size() + joint_state_interfaces_.size());
247
248 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
249 // maps.
250 for (const auto & description : unlisted_interface_descriptions)
251 {
252 auto name = description.get_name();
253 unlisted_state_interfaces_.insert(std::make_pair(name, description));
254 auto state_interface = std::make_shared<StateInterface>(description);
255 actuator_states_.insert(std::make_pair(name, state_interface));
256 unlisted_states_.push_back(state_interface);
257 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
258 }
259
260 for (const auto & [name, descr] : joint_state_interfaces_)
261 {
262 auto state_interface = std::make_shared<StateInterface>(descr);
263 actuator_states_.insert(std::make_pair(name, state_interface));
264 joint_states_.push_back(state_interface);
265 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
266 }
267 return state_interfaces;
268 }
269
271
282 [[deprecated(
283 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
284 "Exporting is "
285 "handled "
286 "by the Framework.")]] virtual std::vector<CommandInterface>
288 {
289 // return empty vector by default. For backward compatibility we try calling
290 // export_command_interfaces() and only when empty vector is returned call
291 // on_export_command_interfaces()
292 return {};
293 }
294
301 virtual std::vector<hardware_interface::InterfaceDescription>
303 {
304 // return empty vector by default.
305 return {};
306 }
307
315 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
316 {
317 // import the unlisted interfaces
318 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
320
321 std::vector<CommandInterface::SharedPtr> command_interfaces;
322 command_interfaces.reserve(
323 unlisted_interface_descriptions.size() + joint_command_interfaces_.size());
324
325 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
326 // maps.
327 for (const auto & description : unlisted_interface_descriptions)
328 {
329 auto name = description.get_name();
330 unlisted_command_interfaces_.insert(std::make_pair(name, description));
331 auto command_interface = std::make_shared<CommandInterface>(description);
332 actuator_commands_.insert(std::make_pair(name, command_interface));
333 unlisted_commands_.push_back(command_interface);
334 command_interfaces.push_back(command_interface);
335 }
336
337 for (const auto & [name, descr] : joint_command_interfaces_)
338 {
339 auto command_interface = std::make_shared<CommandInterface>(descr);
340 actuator_commands_.insert(std::make_pair(name, command_interface));
341 joint_commands_.push_back(command_interface);
342 command_interfaces.push_back(command_interface);
343 }
344
345 return command_interfaces;
346 }
348
360 virtual return_type prepare_command_mode_switch(
361 const std::vector<std::string> & /*start_interfaces*/,
362 const std::vector<std::string> & /*stop_interfaces*/)
363 {
364 return return_type::OK;
365 }
366
367 // Perform switching to the new command interface.
379 virtual return_type perform_command_mode_switch(
380 const std::vector<std::string> & /*start_interfaces*/,
381 const std::vector<std::string> & /*stop_interfaces*/)
382 {
383 return return_type::OK;
384 }
385
387
398 const rclcpp::Time & time, const rclcpp::Duration & period)
399 {
401 status.result = return_type::ERROR;
402 if (info_.is_async)
403 {
404 status.result = read_return_info_.load(std::memory_order_acquire);
405 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
406 if (read_exec_time.count() > 0)
407 {
408 status.execution_time = read_exec_time;
409 }
410 const auto result = async_handler_->trigger_async_callback(time, period);
411 status.successful = result.first;
412 if (!status.successful)
413 {
414 RCLCPP_WARN(
415 get_logger(),
416 "Trigger read/write called while the previous async trigger is still in progress for "
417 "hardware interface : '%s'. Failed to trigger read/write cycle!",
418 info_.name.c_str());
419 status.result = return_type::OK;
420 return status;
421 }
422 }
423 else
424 {
425 const auto start_time = std::chrono::steady_clock::now();
426 status.successful = true;
427 status.result = read(time, period);
428 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
429 std::chrono::steady_clock::now() - start_time);
430 }
431 return status;
432 }
433
435
444 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
445
447
457 const rclcpp::Time & time, const rclcpp::Duration & period)
458 {
460 status.result = return_type::ERROR;
461 if (info_.is_async)
462 {
463 status.successful = true;
464 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
465 if (write_exec_time.count() > 0)
466 {
467 status.execution_time = write_exec_time;
468 }
469 status.result = write_return_info_.load(std::memory_order_acquire);
470 }
471 else
472 {
473 const auto start_time = std::chrono::steady_clock::now();
474 status.successful = true;
475 status.result = write(time, period);
476 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
477 std::chrono::steady_clock::now() - start_time);
478 }
479 return status;
480 }
481
483
491 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
492
494
497 const std::string & get_name() const { return info_.name; }
498
500
503 const std::string & get_group_name() const { return info_.group; }
504
506
509 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
510
512
515 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
516 {
517 lifecycle_state_ = new_state;
518 }
519
520 template <typename T>
521 void set_state(const std::string & interface_name, const T & value)
522 {
523 auto it = actuator_states_.find(interface_name);
524 if (it == actuator_states_.end())
525 {
526 throw std::runtime_error(
527 "State interface not found: " + interface_name +
528 " in actuator hardware component: " + info_.name + ". This should not happen.");
529 }
530 auto & handle = it->second;
531 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
532 std::ignore = handle->set_value(lock, value);
533 }
534
535 template <typename T = double>
536 T get_state(const std::string & interface_name) const
537 {
538 auto it = actuator_states_.find(interface_name);
539 if (it == actuator_states_.end())
540 {
541 throw std::runtime_error(
542 "State interface not found: " + interface_name +
543 " in actuator hardware component: " + info_.name + ". This should not happen.");
544 }
545 auto & handle = it->second;
546 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
547 const auto opt_value = handle->get_optional<T>(lock);
548 if (!opt_value)
549 {
550 throw std::runtime_error(
551 "Failed to get state value from interface: " + interface_name +
552 ". This should not happen.");
553 }
554 return opt_value.value();
555 }
556
557 void set_command(const std::string & interface_name, const double & value)
558 {
559 auto it = actuator_commands_.find(interface_name);
560 if (it == actuator_commands_.end())
561 {
562 throw std::runtime_error(
563 "Command interface not found: " + interface_name +
564 " in actuator hardware component: " + info_.name + ". This should not happen.");
565 }
566 auto & handle = it->second;
567 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
568 std::ignore = handle->set_value(lock, value);
569 }
570
571 template <typename T = double>
572 T get_command(const std::string & interface_name) const
573 {
574 auto it = actuator_commands_.find(interface_name);
575 if (it == actuator_commands_.end())
576 {
577 throw std::runtime_error(
578 "Command interface not found: " + interface_name +
579 " in actuator hardware component: " + info_.name + ". This should not happen.");
580 }
581 auto & handle = it->second;
582 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
583 const auto opt_value = handle->get_optional<double>(lock);
584 if (!opt_value)
585 {
586 throw std::runtime_error(
587 "Failed to get command value from interface: " + interface_name +
588 ". This should not happen.");
589 }
590 return opt_value.value();
591 }
592
594
597 rclcpp::Logger get_logger() const { return actuator_logger_; }
598
600
603 rclcpp::Clock::SharedPtr get_clock() const { return actuator_clock_; }
604
606
609 const HardwareInfo & get_hardware_info() const { return info_; }
610
612
616 {
617 read_return_info_.store(return_type::OK, std::memory_order_release);
618 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
619 write_return_info_.store(return_type::OK, std::memory_order_release);
620 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
621 }
622
624
627 void enable_introspection(bool enable)
628 {
629 if (enable)
630 {
631 stats_registrations_.enableAll();
632 }
633 else
634 {
635 stats_registrations_.disableAll();
636 }
637 }
638
639protected:
640 HardwareInfo info_;
641 // interface names to InterfaceDescription
642 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
643 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
644
645 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
646 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
647
648 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
649 std::vector<StateInterface::SharedPtr> joint_states_;
650 std::vector<CommandInterface::SharedPtr> joint_commands_;
651
652 std::vector<StateInterface::SharedPtr> unlisted_states_;
653 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
654
655 rclcpp_lifecycle::State lifecycle_state_;
656 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
657
658private:
659 rclcpp::Clock::SharedPtr actuator_clock_;
660 rclcpp::Logger actuator_logger_;
661 // interface names to Handle accessed through getters/setters
662 std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_;
663 std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_;
664 std::atomic<return_type> read_return_info_ = return_type::OK;
665 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
666 std::atomic<return_type> write_return_info_ = return_type::OK;
667 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
668
669protected:
670 pal_statistics::RegistrationsRAII stats_registrations_;
671};
672
673} // namespace hardware_interface
674#endif // HARDWARE_INTERFACE__ACTUATOR_INTERFACE_HPP_
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition actuator_interface.hpp:92
virtual return_type read(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Read the current state values from the actuator.
virtual std::vector< CommandInterface > export_command_interfaces()
Exports all command interfaces for this hardware interface.
Definition actuator_interface.hpp:287
virtual CallbackReturn on_init(const HardwareInfo &hardware_info)
Initialization of the hardware interface from data parsed from the robot's URDF.
Definition actuator_interface.hpp:185
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition actuator_interface.hpp:238
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition actuator_interface.hpp:503
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition actuator_interface.hpp:302
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition actuator_interface.hpp:123
HardwareComponentCycleStatus trigger_read(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the read method synchronously or asynchronously depending on the HardwareInfo.
Definition actuator_interface.hpp:397
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
Definition actuator_interface.hpp:139
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition actuator_interface.hpp:225
rclcpp::Logger get_logger() const
Get the logger of the ActuatorInterface.
Definition actuator_interface.hpp:597
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition actuator_interface.hpp:210
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:515
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition actuator_interface.hpp:315
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:509
const HardwareInfo & get_hardware_info() const
Get the hardware info of the ActuatorInterface.
Definition actuator_interface.hpp:609
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition actuator_interface.hpp:627
const std::string & get_name() const
Get name of the actuator hardware.
Definition actuator_interface.hpp:497
HardwareComponentCycleStatus trigger_write(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the write method synchronously or asynchronously depending on the HardwareInfo.
Definition actuator_interface.hpp:456
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition actuator_interface.hpp:615
ActuatorInterface(const ActuatorInterface &other)=delete
ActuatorInterface copy constructor is actively deleted.
virtual return_type prepare_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Prepare for a new command interface switch.
Definition actuator_interface.hpp:360
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition actuator_interface.hpp:379
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the ActuatorInterface.
Definition actuator_interface.hpp:603
Definition actuator.hpp:33
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1045
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