ros2_control - rolling
Loading...
Searching...
No Matches
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 <fmt/compile.h>
19
20#include <limits>
21#include <memory>
22#include <string>
23#include <unordered_map>
24#include <utility>
25#include <vector>
26
27#include "hardware_interface/component_parser.hpp"
28#include "hardware_interface/handle.hpp"
29#include "hardware_interface/hardware_info.hpp"
30#include "hardware_interface/introspection.hpp"
31#include "hardware_interface/types/hardware_interface_return_values.hpp"
32#include "hardware_interface/types/lifecycle_state_names.hpp"
33#include "hardware_interface/types/trigger_type.hpp"
34#include "lifecycle_msgs/msg/state.hpp"
35#include "rclcpp/duration.hpp"
36#include "rclcpp/logger.hpp"
37#include "rclcpp/node_interfaces/node_clock_interface.hpp"
38#include "rclcpp/time.hpp"
39#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
40#include "rclcpp_lifecycle/state.hpp"
41#include "realtime_tools/async_function_handler.hpp"
42
43namespace hardware_interface
44{
45
46using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
47
49
93class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
94{
95public:
97 : lifecycle_state_(
98 rclcpp_lifecycle::State(
99 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
100 actuator_logger_(rclcpp::get_logger("actuator_interface"))
101 {
102 }
103
105
109 ActuatorInterface(const ActuatorInterface & other) = delete;
110
111 ActuatorInterface(ActuatorInterface && other) = delete;
112
113 virtual ~ActuatorInterface() = default;
114
117
124 CallbackReturn init(
125 const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
126 {
127 actuator_clock_ = clock;
128 actuator_logger_ = logger.get_child("hardware_component.actuator." + hardware_info.name);
129 info_ = hardware_info;
130 if (info_.is_async)
131 {
132 RCLCPP_INFO_STREAM(
133 get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
134 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
135 async_handler_->init(
136 [this](const rclcpp::Time & time, const rclcpp::Duration & period)
137 {
138 const auto read_start_time = std::chrono::steady_clock::now();
139 const auto ret_read = read(time, period);
140 const auto read_end_time = std::chrono::steady_clock::now();
141 read_return_info_.store(ret_read, std::memory_order_release);
142 read_execution_time_.store(
143 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
144 std::memory_order_release);
145 if (ret_read != return_type::OK)
146 {
147 return ret_read;
148 }
149 const auto write_start_time = std::chrono::steady_clock::now();
150 const auto ret_write = write(time, period);
151 const auto write_end_time = std::chrono::steady_clock::now();
152 write_return_info_.store(ret_write, std::memory_order_release);
153 write_execution_time_.store(
154 std::chrono::duration_cast<std::chrono::nanoseconds>(write_end_time - write_start_time),
155 std::memory_order_release);
156 return ret_write;
157 },
158 info_.thread_priority);
159 async_handler_->start_thread();
160 }
161 return on_init(hardware_info);
162 };
163
165
170 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
171 {
172 info_ = hardware_info;
173 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
174 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
175 return CallbackReturn::SUCCESS;
176 };
177
179
190 [[deprecated(
191 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
192 "Exporting is "
193 "handled "
194 "by the Framework.")]] virtual std::vector<StateInterface>
196 {
197 // return empty vector by default. For backward compatibility we try calling
198 // export_state_interfaces() and only when empty vector is returned call
199 // on_export_state_interfaces()
200 return {};
201 }
202
209 virtual std::vector<hardware_interface::InterfaceDescription>
211 {
212 // return empty vector by default.
213 return {};
214 }
215
223 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
224 {
225 // import the unlisted interfaces
226 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
228
229 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
230 state_interfaces.reserve(
231 unlisted_interface_descriptions.size() + joint_state_interfaces_.size());
232
233 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
234 // maps.
235 for (const auto & description : unlisted_interface_descriptions)
236 {
237 auto name = description.get_name();
238 unlisted_state_interfaces_.insert(std::make_pair(name, description));
239 auto state_interface = std::make_shared<StateInterface>(description);
240 actuator_states_.insert(std::make_pair(name, state_interface));
241 unlisted_states_.push_back(state_interface);
242 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
243 }
244
245 for (const auto & [name, descr] : joint_state_interfaces_)
246 {
247 auto state_interface = std::make_shared<StateInterface>(descr);
248 actuator_states_.insert(std::make_pair(name, state_interface));
249 joint_states_.push_back(state_interface);
250 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
251 }
252 return state_interfaces;
253 }
254
256
267 [[deprecated(
268 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
269 "Exporting is "
270 "handled "
271 "by the Framework.")]] virtual std::vector<CommandInterface>
273 {
274 // return empty vector by default. For backward compatibility we try calling
275 // export_command_interfaces() and only when empty vector is returned call
276 // on_export_command_interfaces()
277 return {};
278 }
279
286 virtual std::vector<hardware_interface::InterfaceDescription>
288 {
289 // return empty vector by default.
290 return {};
291 }
292
300 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
301 {
302 // import the unlisted interfaces
303 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
305
306 std::vector<CommandInterface::SharedPtr> command_interfaces;
307 command_interfaces.reserve(
308 unlisted_interface_descriptions.size() + joint_command_interfaces_.size());
309
310 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
311 // maps.
312 for (const auto & description : unlisted_interface_descriptions)
313 {
314 auto name = description.get_name();
315 unlisted_command_interfaces_.insert(std::make_pair(name, description));
316 auto command_interface = std::make_shared<CommandInterface>(description);
317 actuator_commands_.insert(std::make_pair(name, command_interface));
318 unlisted_commands_.push_back(command_interface);
319 command_interfaces.push_back(command_interface);
320 }
321
322 for (const auto & [name, descr] : joint_command_interfaces_)
323 {
324 auto command_interface = std::make_shared<CommandInterface>(descr);
325 actuator_commands_.insert(std::make_pair(name, command_interface));
326 joint_commands_.push_back(command_interface);
327 command_interfaces.push_back(command_interface);
328 }
329
330 return command_interfaces;
331 }
333
343 virtual return_type prepare_command_mode_switch(
344 const std::vector<std::string> & /*start_interfaces*/,
345 const std::vector<std::string> & /*stop_interfaces*/)
346 {
347 return return_type::OK;
348 }
349
350 // Perform switching to the new command interface.
360 virtual return_type perform_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
368
379 const rclcpp::Time & time, const rclcpp::Duration & period)
380 {
382 status.result = return_type::ERROR;
383 if (info_.is_async)
384 {
385 status.result = read_return_info_.load(std::memory_order_acquire);
386 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
387 if (read_exec_time.count() > 0)
388 {
389 status.execution_time = read_exec_time;
390 }
391 const auto result = async_handler_->trigger_async_callback(time, period);
392 status.successful = result.first;
393 if (!status.successful)
394 {
395 RCLCPP_WARN(
396 get_logger(),
397 "Trigger read/write called while the previous async trigger is still in progress for "
398 "hardware interface : '%s'. Failed to trigger read/write cycle!",
399 info_.name.c_str());
400 status.result = return_type::OK;
401 return status;
402 }
403 }
404 else
405 {
406 const auto start_time = std::chrono::steady_clock::now();
407 status.successful = true;
408 status.result = read(time, period);
409 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
410 std::chrono::steady_clock::now() - start_time);
411 }
412 return status;
413 }
414
416
425 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
426
428
438 const rclcpp::Time & time, const rclcpp::Duration & period)
439 {
441 status.result = return_type::ERROR;
442 if (info_.is_async)
443 {
444 status.successful = true;
445 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
446 if (write_exec_time.count() > 0)
447 {
448 status.execution_time = write_exec_time;
449 }
450 status.result = write_return_info_.load(std::memory_order_acquire);
451 }
452 else
453 {
454 const auto start_time = std::chrono::steady_clock::now();
455 status.successful = true;
456 status.result = write(time, period);
457 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
458 std::chrono::steady_clock::now() - start_time);
459 }
460 return status;
461 }
462
464
472 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
473
475
478 const std::string & get_name() const { return info_.name; }
479
481
484 const std::string & get_group_name() const { return info_.group; }
485
487
490 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
491
493
496 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
497 {
498 lifecycle_state_ = new_state;
499 }
500
501 template <typename T>
502 void set_state(const std::string & interface_name, const T & value)
503 {
504 auto it = actuator_states_.find(interface_name);
505 if (it == actuator_states_.end())
506 {
507 throw std::runtime_error(
508 fmt::format(
509 FMT_COMPILE(
510 "State interface not found: {} in actuator hardware component: {}. "
511 "This should not happen."),
512 interface_name, info_.name));
513 }
514 auto & handle = it->second;
515 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
516 std::ignore = handle->set_value(lock, value);
517 }
518
519 template <typename T = double>
520 T get_state(const std::string & interface_name) const
521 {
522 auto it = actuator_states_.find(interface_name);
523 if (it == actuator_states_.end())
524 {
525 throw std::runtime_error(
526 fmt::format(
527 FMT_COMPILE(
528 "State interface not found: {} in actuator hardware component: {}. "
529 "This should not happen."),
530 interface_name, info_.name));
531 }
532 auto & handle = it->second;
533 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
534 const auto opt_value = handle->get_optional<T>(lock);
535 if (!opt_value)
536 {
537 throw std::runtime_error(
538 fmt::format(
539 FMT_COMPILE("Failed to get state value from interface: {}. This should not happen."),
540 interface_name));
541 }
542 return opt_value.value();
543 }
544
545 void set_command(const std::string & interface_name, const double & value)
546 {
547 auto it = actuator_commands_.find(interface_name);
548 if (it == actuator_commands_.end())
549 {
550 throw std::runtime_error(
551 fmt::format(
552 FMT_COMPILE(
553 "Command interface not found: {} in actuator hardware component: {}. "
554 "This should not happen."),
555 interface_name, info_.name));
556 }
557 auto & handle = it->second;
558 std::unique_lock<std::shared_mutex> lock(handle->get_mutex());
559 std::ignore = handle->set_value(lock, value);
560 }
561
562 template <typename T = double>
563 T get_command(const std::string & interface_name) const
564 {
565 auto it = actuator_commands_.find(interface_name);
566 if (it == actuator_commands_.end())
567 {
568 throw std::runtime_error(
569 fmt::format(
570 FMT_COMPILE(
571 "Command interface not found: {} in actuator hardware component: {}. "
572 "This should not happen."),
573 interface_name, info_.name));
574 }
575 auto & handle = it->second;
576 std::shared_lock<std::shared_mutex> lock(handle->get_mutex());
577 const auto opt_value = handle->get_optional<double>(lock);
578 if (!opt_value)
579 {
580 throw std::runtime_error(
581 fmt::format(
582 FMT_COMPILE("Failed to get command value from interface: {}. This should not happen."),
583 interface_name));
584 }
585 return opt_value.value();
586 }
587
589
592 rclcpp::Logger get_logger() const { return actuator_logger_; }
593
595
598 rclcpp::Clock::SharedPtr get_clock() const { return actuator_clock_; }
599
601
604 const HardwareInfo & get_hardware_info() const { return info_; }
605
607
611 {
612 read_return_info_.store(return_type::OK, std::memory_order_release);
613 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
614 write_return_info_.store(return_type::OK, std::memory_order_release);
615 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
616 }
617
619
622 void enable_introspection(bool enable)
623 {
624 if (enable)
625 {
626 stats_registrations_.enableAll();
627 }
628 else
629 {
630 stats_registrations_.disableAll();
631 }
632 }
633
634protected:
635 HardwareInfo info_;
636 // interface names to InterfaceDescription
637 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
638 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
639
640 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
641 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
642
643 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
644 std::vector<StateInterface::SharedPtr> joint_states_;
645 std::vector<CommandInterface::SharedPtr> joint_commands_;
646
647 std::vector<StateInterface::SharedPtr> unlisted_states_;
648 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
649
650 rclcpp_lifecycle::State lifecycle_state_;
651 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
652
653private:
654 rclcpp::Clock::SharedPtr actuator_clock_;
655 rclcpp::Logger actuator_logger_;
656 // interface names to Handle accessed through getters/setters
657 std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_;
658 std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_;
659 std::atomic<return_type> read_return_info_ = return_type::OK;
660 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
661 std::atomic<return_type> write_return_info_ = return_type::OK;
662 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
663
664protected:
665 pal_statistics::RegistrationsRAII stats_registrations_;
666};
667
668} // namespace hardware_interface
669#endif // HARDWARE_INTERFACE__ACTUATOR_INTERFACE_HPP_
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
Definition actuator_interface.hpp:94
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:272
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:170
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition actuator_interface.hpp:223
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition actuator_interface.hpp:484
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition actuator_interface.hpp:287
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:378
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:124
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition actuator_interface.hpp:210
rclcpp::Logger get_logger() const
Get the logger of the ActuatorInterface.
Definition actuator_interface.hpp:592
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition actuator_interface.hpp:195
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:496
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition actuator_interface.hpp:300
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:490
const HardwareInfo & get_hardware_info() const
Get the hardware info of the ActuatorInterface.
Definition actuator_interface.hpp:604
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition actuator_interface.hpp:622
const std::string & get_name() const
Get name of the actuator hardware.
Definition actuator_interface.hpp:478
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:437
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition actuator_interface.hpp:610
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:343
virtual return_type perform_command_mode_switch(const std::vector< std::string > &, const std::vector< std::string > &)
Definition actuator_interface.hpp:360
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the ActuatorInterface.
Definition actuator_interface.hpp:598
Definition actuator.hpp:34
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1067
std::vector< InterfaceDescription > parse_state_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1034
Definition hardware_interface_return_values.hpp:41
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:234
int thread_priority
Async thread priority.
Definition hardware_info.hpp:246
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:240
bool is_async
Component is async.
Definition hardware_info.hpp:244
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:255
std::string name
Name of the hardware.
Definition hardware_info.hpp:236