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 <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_(rclcpp_lifecycle::State(
96 lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
97 actuator_logger_(rclcpp::get_logger("actuator_interface"))
98 {
99 }
100
102
106 ActuatorInterface(const ActuatorInterface & other) = delete;
107
108 ActuatorInterface(ActuatorInterface && other) = delete;
109
110 virtual ~ActuatorInterface() = default;
111
114
121 CallbackReturn init(
122 const HardwareInfo & hardware_info, rclcpp::Logger logger,
123 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
124 {
125 clock_interface_ = clock_interface;
126 actuator_logger_ = logger.get_child("hardware_component.actuator." + hardware_info.name);
127 info_ = hardware_info;
128 if (info_.is_async)
129 {
130 RCLCPP_INFO_STREAM(
131 get_logger(), "Starting async handler with scheduler priority: " << info_.thread_priority);
132 async_handler_ = std::make_unique<realtime_tools::AsyncFunctionHandler<return_type>>();
133 async_handler_->init(
134 [this](const rclcpp::Time & time, const rclcpp::Duration & period)
135 {
136 const auto read_start_time = std::chrono::steady_clock::now();
137 const auto ret_read = read(time, period);
138 const auto read_end_time = std::chrono::steady_clock::now();
139 read_return_info_.store(ret_read, std::memory_order_release);
140 read_execution_time_.store(
141 std::chrono::duration_cast<std::chrono::nanoseconds>(read_end_time - read_start_time),
142 std::memory_order_release);
143 if (ret_read != return_type::OK)
144 {
145 return ret_read;
146 }
147 const auto write_start_time = std::chrono::steady_clock::now();
148 const auto ret_write = write(time, period);
149 const auto write_end_time = std::chrono::steady_clock::now();
150 write_return_info_.store(ret_write, std::memory_order_release);
151 write_execution_time_.store(
152 std::chrono::duration_cast<std::chrono::nanoseconds>(write_end_time - write_start_time),
153 std::memory_order_release);
154 return ret_write;
155 },
156 info_.thread_priority);
157 async_handler_->start_thread();
158 }
159 return on_init(hardware_info);
160 };
161
163
168 virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
169 {
170 info_ = hardware_info;
171 parse_state_interface_descriptions(info_.joints, joint_state_interfaces_);
172 parse_command_interface_descriptions(info_.joints, joint_command_interfaces_);
173 return CallbackReturn::SUCCESS;
174 };
175
177
188 [[deprecated(
189 "Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
190 "Exporting is "
191 "handled "
192 "by the Framework.")]] virtual std::vector<StateInterface>
194 {
195 // return empty vector by default. For backward compatibility we try calling
196 // export_state_interfaces() and only when empty vector is returned call
197 // on_export_state_interfaces()
198 return {};
199 }
200
207 virtual std::vector<hardware_interface::InterfaceDescription>
209 {
210 // return empty vector by default.
211 return {};
212 }
213
221 virtual std::vector<StateInterface::ConstSharedPtr> on_export_state_interfaces()
222 {
223 // import the unlisted interfaces
224 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
226
227 std::vector<StateInterface::ConstSharedPtr> state_interfaces;
228 state_interfaces.reserve(
229 unlisted_interface_descriptions.size() + joint_state_interfaces_.size());
230
231 // add InterfaceDescriptions and create the StateInterfaces from the descriptions and add to
232 // maps.
233 for (const auto & description : unlisted_interface_descriptions)
234 {
235 auto name = description.get_name();
236 unlisted_state_interfaces_.insert(std::make_pair(name, description));
237 auto state_interface = std::make_shared<StateInterface>(description);
238 actuator_states_.insert(std::make_pair(name, state_interface));
239 unlisted_states_.push_back(state_interface);
240 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
241 }
242
243 for (const auto & [name, descr] : joint_state_interfaces_)
244 {
245 auto state_interface = std::make_shared<StateInterface>(descr);
246 actuator_states_.insert(std::make_pair(name, state_interface));
247 joint_states_.push_back(state_interface);
248 state_interfaces.push_back(std::const_pointer_cast<const StateInterface>(state_interface));
249 }
250 return state_interfaces;
251 }
252
254
265 [[deprecated(
266 "Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
267 "Exporting is "
268 "handled "
269 "by the Framework.")]] virtual std::vector<CommandInterface>
271 {
272 // return empty vector by default. For backward compatibility we try calling
273 // export_command_interfaces() and only when empty vector is returned call
274 // on_export_command_interfaces()
275 return {};
276 }
277
284 virtual std::vector<hardware_interface::InterfaceDescription>
286 {
287 // return empty vector by default.
288 return {};
289 }
290
298 virtual std::vector<CommandInterface::SharedPtr> on_export_command_interfaces()
299 {
300 // import the unlisted interfaces
301 std::vector<hardware_interface::InterfaceDescription> unlisted_interface_descriptions =
303
304 std::vector<CommandInterface::SharedPtr> command_interfaces;
305 command_interfaces.reserve(
306 unlisted_interface_descriptions.size() + joint_command_interfaces_.size());
307
308 // add InterfaceDescriptions and create the CommandInterfaces from the descriptions and add to
309 // maps.
310 for (const auto & description : unlisted_interface_descriptions)
311 {
312 auto name = description.get_name();
313 unlisted_command_interfaces_.insert(std::make_pair(name, description));
314 auto command_interface = std::make_shared<CommandInterface>(description);
315 actuator_commands_.insert(std::make_pair(name, command_interface));
316 unlisted_commands_.push_back(command_interface);
317 command_interfaces.push_back(command_interface);
318 }
319
320 for (const auto & [name, descr] : joint_command_interfaces_)
321 {
322 auto command_interface = std::make_shared<CommandInterface>(descr);
323 actuator_commands_.insert(std::make_pair(name, command_interface));
324 joint_commands_.push_back(command_interface);
325 command_interfaces.push_back(command_interface);
326 }
327
328 return command_interfaces;
329 }
331
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.
362 virtual return_type perform_command_mode_switch(
363 const std::vector<std::string> & /*start_interfaces*/,
364 const std::vector<std::string> & /*stop_interfaces*/)
365 {
366 return return_type::OK;
367 }
368
370
381 const rclcpp::Time & time, const rclcpp::Duration & period)
382 {
384 status.result = return_type::ERROR;
385 if (info_.is_async)
386 {
387 status.result = read_return_info_.load(std::memory_order_acquire);
388 const auto read_exec_time = read_execution_time_.load(std::memory_order_acquire);
389 if (read_exec_time.count() > 0)
390 {
391 status.execution_time = read_exec_time;
392 }
393 const auto result = async_handler_->trigger_async_callback(time, period);
394 status.successful = result.first;
395 if (!status.successful)
396 {
397 RCLCPP_WARN(
398 get_logger(),
399 "Trigger read/write called while the previous async trigger is still in progress for "
400 "hardware interface : '%s'. Failed to trigger read/write cycle!",
401 info_.name.c_str());
402 status.result = return_type::OK;
403 return status;
404 }
405 }
406 else
407 {
408 const auto start_time = std::chrono::steady_clock::now();
409 status.successful = true;
410 status.result = read(time, period);
411 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
412 std::chrono::steady_clock::now() - start_time);
413 }
414 return status;
415 }
416
418
427 virtual return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
428
430
440 const rclcpp::Time & time, const rclcpp::Duration & period)
441 {
443 status.result = return_type::ERROR;
444 if (info_.is_async)
445 {
446 status.successful = true;
447 const auto write_exec_time = write_execution_time_.load(std::memory_order_acquire);
448 if (write_exec_time.count() > 0)
449 {
450 status.execution_time = write_exec_time;
451 }
452 status.result = write_return_info_.load(std::memory_order_acquire);
453 }
454 else
455 {
456 const auto start_time = std::chrono::steady_clock::now();
457 status.successful = true;
458 status.result = write(time, period);
459 status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
460 std::chrono::steady_clock::now() - start_time);
461 }
462 return status;
463 }
464
466
474 virtual return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;
475
477
480 const std::string & get_name() const { return info_.name; }
481
483
486 const std::string & get_group_name() const { return info_.group; }
487
489
492 const rclcpp_lifecycle::State & get_lifecycle_state() const { return lifecycle_state_; }
493
495
498 void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)
499 {
500 lifecycle_state_ = new_state;
501 }
502
503 void set_state(const std::string & interface_name, const double & value)
504 {
505 actuator_states_.at(interface_name)->set_value(value);
506 }
507
508 double get_state(const std::string & interface_name) const
509 {
510 return actuator_states_.at(interface_name)->get_value();
511 }
512
513 void set_command(const std::string & interface_name, const double & value)
514 {
515 actuator_commands_.at(interface_name)->set_value(value);
516 }
517
518 double get_command(const std::string & interface_name) const
519 {
520 return actuator_commands_.at(interface_name)->get_value();
521 }
522
524
527 rclcpp::Logger get_logger() const { return actuator_logger_; }
528
530
533 rclcpp::Clock::SharedPtr get_clock() const { return clock_interface_->get_clock(); }
534
536
539 const HardwareInfo & get_hardware_info() const { return info_; }
540
542
546 {
547 read_return_info_.store(return_type::OK, std::memory_order_release);
548 read_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
549 write_return_info_.store(return_type::OK, std::memory_order_release);
550 write_execution_time_.store(std::chrono::nanoseconds::zero(), std::memory_order_release);
551 }
552
554
557 void enable_introspection(bool enable)
558 {
559 if (enable)
560 {
561 stats_registrations_.enableAll();
562 }
563 else
564 {
565 stats_registrations_.disableAll();
566 }
567 }
568
569protected:
570 HardwareInfo info_;
571 // interface names to InterfaceDescription
572 std::unordered_map<std::string, InterfaceDescription> joint_state_interfaces_;
573 std::unordered_map<std::string, InterfaceDescription> joint_command_interfaces_;
574
575 std::unordered_map<std::string, InterfaceDescription> unlisted_state_interfaces_;
576 std::unordered_map<std::string, InterfaceDescription> unlisted_command_interfaces_;
577
578 // Exported Command- and StateInterfaces in order they are listed in the hardware description.
579 std::vector<StateInterface::SharedPtr> joint_states_;
580 std::vector<CommandInterface::SharedPtr> joint_commands_;
581
582 std::vector<StateInterface::SharedPtr> unlisted_states_;
583 std::vector<CommandInterface::SharedPtr> unlisted_commands_;
584
585 rclcpp_lifecycle::State lifecycle_state_;
586 std::unique_ptr<realtime_tools::AsyncFunctionHandler<return_type>> async_handler_;
587
588private:
589 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
590 rclcpp::Logger actuator_logger_;
591 // interface names to Handle accessed through getters/setters
592 std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_;
593 std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_;
594 std::atomic<return_type> read_return_info_ = return_type::OK;
595 std::atomic<std::chrono::nanoseconds> read_execution_time_ = std::chrono::nanoseconds::zero();
596 std::atomic<return_type> write_return_info_ = return_type::OK;
597 std::atomic<std::chrono::nanoseconds> write_execution_time_ = std::chrono::nanoseconds::zero();
598
599protected:
600 pal_statistics::RegistrationsRAII stats_registrations_;
601};
602
603} // namespace hardware_interface
604#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:270
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:168
virtual std::vector< StateInterface::ConstSharedPtr > on_export_state_interfaces()
Definition actuator_interface.hpp:221
const std::string & get_group_name() const
Get name of the actuator hardware group to which it belongs to.
Definition actuator_interface.hpp:486
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_command_interface_descriptions()
Definition actuator_interface.hpp:285
CallbackReturn init(const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
Definition actuator_interface.hpp:121
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:380
virtual return_type write(const rclcpp::Time &time, const rclcpp::Duration &period)=0
Write the current command values to the actuator.
virtual std::vector< hardware_interface::InterfaceDescription > export_unlisted_state_interface_descriptions()
Definition actuator_interface.hpp:208
rclcpp::Logger get_logger() const
Get the logger of the ActuatorInterface.
Definition actuator_interface.hpp:527
virtual std::vector< StateInterface > export_state_interfaces()
Exports all state interfaces for this hardware interface.
Definition actuator_interface.hpp:193
void set_lifecycle_state(const rclcpp_lifecycle::State &new_state)
Set life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:498
virtual std::vector< CommandInterface::SharedPtr > on_export_command_interfaces()
Definition actuator_interface.hpp:298
const rclcpp_lifecycle::State & get_lifecycle_state() const
Get life-cycle state of the actuator hardware.
Definition actuator_interface.hpp:492
const HardwareInfo & get_hardware_info() const
Get the hardware info of the ActuatorInterface.
Definition actuator_interface.hpp:539
void enable_introspection(bool enable)
Enable or disable introspection of the hardware.
Definition actuator_interface.hpp:557
const std::string & get_name() const
Get name of the actuator hardware.
Definition actuator_interface.hpp:480
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:439
void prepare_for_activation()
Prepare for the activation of the hardware.
Definition actuator_interface.hpp:545
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:362
rclcpp::Clock::SharedPtr get_clock() const
Get the clock of the ActuatorInterface.
Definition actuator_interface.hpp:533
Definition actuator.hpp:33
std::vector< InterfaceDescription > parse_command_interface_descriptions(const std::vector< ComponentInfo > &component_info)
Definition component_parser.cpp:1036
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