|
15 | 15 | #ifndef HARDWARE_INTERFACE__ACTUATOR_HPP_ |
16 | 16 | #define HARDWARE_INTERFACE__ACTUATOR_HPP_ |
17 | 17 |
|
18 | | -#include <memory> |
19 | | -#include <string> |
20 | | -#include <vector> |
21 | | - |
22 | 18 | #include "hardware_interface/actuator_interface.hpp" |
23 | | -#include "hardware_interface/handle.hpp" |
24 | | -#include "hardware_interface/hardware_info.hpp" |
25 | | -#include "hardware_interface/types/hardware_interface_return_values.hpp" |
26 | | -#include "hardware_interface/types/statistics_types.hpp" |
27 | | -#include "rclcpp/duration.hpp" |
28 | | -#include "rclcpp/logger.hpp" |
29 | | -#include "rclcpp/node_interfaces/node_clock_interface.hpp" |
30 | | -#include "rclcpp/time.hpp" |
31 | | -#include "rclcpp_lifecycle/state.hpp" |
| 19 | +#include "hardware_interface/hardware_component.hpp" |
32 | 20 |
|
33 | 21 | namespace hardware_interface |
34 | 22 | { |
35 | | -class ActuatorInterface; |
36 | | - |
37 | | -class Actuator final |
38 | | -{ |
39 | | -public: |
40 | | - Actuator() = default; |
41 | | - |
42 | | - explicit Actuator(std::unique_ptr<ActuatorInterface> impl); |
43 | | - |
44 | | - explicit Actuator(Actuator && other) noexcept; |
45 | | - |
46 | | - ~Actuator() = default; |
47 | | - |
48 | | - Actuator(const Actuator & other) = delete; |
49 | | - |
50 | | - Actuator & operator=(const Actuator & other) = delete; |
51 | | - |
52 | | - Actuator & operator=(Actuator && other) = delete; |
53 | | - |
54 | | - [[deprecated( |
55 | | - "Replaced by const rclcpp_lifecycle::State & initialize(const " |
56 | | - "hardware_interface::HardwareComponentParams & params).")]] |
57 | | - const rclcpp_lifecycle::State & initialize( |
58 | | - const HardwareInfo & actuator_info, rclcpp::Logger logger, |
59 | | - rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface); |
60 | | - |
61 | | - [[deprecated( |
62 | | - "Replaced by const rclcpp_lifecycle::State & initialize(const " |
63 | | - "hardware_interface::HardwareComponentParams & params).")]] |
64 | | - const rclcpp_lifecycle::State & initialize( |
65 | | - const HardwareInfo & actuator_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); |
66 | | - |
67 | | - const rclcpp_lifecycle::State & initialize( |
68 | | - const hardware_interface::HardwareComponentParams & params); |
69 | | - |
70 | | - const rclcpp_lifecycle::State & configure(); |
71 | | - |
72 | | - const rclcpp_lifecycle::State & cleanup(); |
73 | | - |
74 | | - const rclcpp_lifecycle::State & shutdown(); |
75 | | - |
76 | | - const rclcpp_lifecycle::State & activate(); |
77 | | - |
78 | | - const rclcpp_lifecycle::State & deactivate(); |
79 | | - |
80 | | - const rclcpp_lifecycle::State & error(); |
81 | | - |
82 | | - std::vector<StateInterface::ConstSharedPtr> export_state_interfaces(); |
83 | | - |
84 | | - std::vector<CommandInterface::SharedPtr> export_command_interfaces(); |
85 | | - |
86 | | - return_type prepare_command_mode_switch( |
87 | | - const std::vector<std::string> & start_interfaces, |
88 | | - const std::vector<std::string> & stop_interfaces); |
89 | | - |
90 | | - return_type perform_command_mode_switch( |
91 | | - const std::vector<std::string> & start_interfaces, |
92 | | - const std::vector<std::string> & stop_interfaces); |
93 | | - |
94 | | - const std::string & get_name() const; |
95 | | - |
96 | | - const std::string & get_group_name() const; |
97 | | - |
98 | | - const rclcpp_lifecycle::State & get_lifecycle_state() const; |
99 | | - |
100 | | - const rclcpp::Time & get_last_read_time() const; |
101 | | - |
102 | | - const rclcpp::Time & get_last_write_time() const; |
103 | | - |
104 | | - const HardwareComponentStatisticsCollector & get_read_statistics() const; |
105 | | - |
106 | | - const HardwareComponentStatisticsCollector & get_write_statistics() const; |
107 | | - |
108 | | - return_type read(const rclcpp::Time & time, const rclcpp::Duration & period); |
109 | | - |
110 | | - return_type write(const rclcpp::Time & time, const rclcpp::Duration & period); |
111 | | - |
112 | | - std::recursive_mutex & get_mutex(); |
113 | | - |
114 | | -private: |
115 | | - std::unique_ptr<ActuatorInterface> impl_; |
116 | | - mutable std::recursive_mutex actuators_mutex_; |
117 | | - // Last read cycle time |
118 | | - rclcpp::Time last_read_cycle_time_; |
119 | | - // Last write cycle time |
120 | | - rclcpp::Time last_write_cycle_time_; |
121 | | - // Component statistics |
122 | | - HardwareComponentStatisticsCollector read_statistics_; |
123 | | - HardwareComponentStatisticsCollector write_statistics_; |
124 | | -}; |
125 | | - |
| 23 | +using Actuator = HardwareComponent; |
126 | 24 | } // namespace hardware_interface |
127 | 25 | #endif // HARDWARE_INTERFACE__ACTUATOR_HPP_ |
0 commit comments