42 explicit Actuator(std::unique_ptr<ActuatorInterface> impl);
48 const rclcpp_lifecycle::State & initialize(
49 const HardwareInfo & actuator_info, rclcpp::Logger logger,
50 rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);
52 const rclcpp_lifecycle::State & initialize(
53 const HardwareInfo & actuator_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock);
55 const rclcpp_lifecycle::State & configure();
57 const rclcpp_lifecycle::State & cleanup();
59 const rclcpp_lifecycle::State & shutdown();
61 const rclcpp_lifecycle::State & activate();
63 const rclcpp_lifecycle::State & deactivate();
65 const rclcpp_lifecycle::State & error();
67 std::vector<StateInterface::ConstSharedPtr> export_state_interfaces();
69 std::vector<CommandInterface::SharedPtr> export_command_interfaces();
71 return_type prepare_command_mode_switch(
72 const std::vector<std::string> & start_interfaces,
73 const std::vector<std::string> & stop_interfaces);
75 return_type perform_command_mode_switch(
76 const std::vector<std::string> & start_interfaces,
77 const std::vector<std::string> & stop_interfaces);
79 const std::string & get_name()
const;
81 const std::string & get_group_name()
const;
83 const rclcpp_lifecycle::State & get_lifecycle_state()
const;
85 const rclcpp::Time & get_last_read_time()
const;
87 const rclcpp::Time & get_last_write_time()
const;
89 const HardwareComponentStatisticsCollector & get_read_statistics()
const;
91 const HardwareComponentStatisticsCollector & get_write_statistics()
const;
93 return_type read(
const rclcpp::Time & time,
const rclcpp::Duration & period);
95 return_type write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
97 std::recursive_mutex & get_mutex();
100 std::unique_ptr<ActuatorInterface> impl_;
101 mutable std::recursive_mutex actuators_mutex_;
103 rclcpp::Time last_read_cycle_time_;
105 rclcpp::Time last_write_cycle_time_;
107 HardwareComponentStatisticsCollector read_statistics_;
108 HardwareComponentStatisticsCollector write_statistics_;