39 HARDWARE_INTERFACE_PUBLIC
40 explicit Actuator(std::unique_ptr<ActuatorInterface> impl);
46 HARDWARE_INTERFACE_PUBLIC
47 const rclcpp_lifecycle::State & initialize(
const HardwareInfo & actuator_info);
49 HARDWARE_INTERFACE_PUBLIC
50 const rclcpp_lifecycle::State & configure();
52 HARDWARE_INTERFACE_PUBLIC
53 const rclcpp_lifecycle::State & cleanup();
55 HARDWARE_INTERFACE_PUBLIC
56 const rclcpp_lifecycle::State & shutdown();
58 HARDWARE_INTERFACE_PUBLIC
59 const rclcpp_lifecycle::State & activate();
61 HARDWARE_INTERFACE_PUBLIC
62 const rclcpp_lifecycle::State & deactivate();
64 HARDWARE_INTERFACE_PUBLIC
65 const rclcpp_lifecycle::State & error();
67 HARDWARE_INTERFACE_PUBLIC
68 std::vector<StateInterface> export_state_interfaces();
70 HARDWARE_INTERFACE_PUBLIC
71 std::vector<CommandInterface> export_command_interfaces();
73 HARDWARE_INTERFACE_PUBLIC
74 return_type prepare_command_mode_switch(
75 const std::vector<std::string> & start_interfaces,
76 const std::vector<std::string> & stop_interfaces);
78 HARDWARE_INTERFACE_PUBLIC
79 return_type perform_command_mode_switch(
80 const std::vector<std::string> & start_interfaces,
81 const std::vector<std::string> & stop_interfaces);
83 HARDWARE_INTERFACE_PUBLIC
84 std::string get_name()
const;
86 HARDWARE_INTERFACE_PUBLIC
87 const rclcpp_lifecycle::State & get_state()
const;
89 HARDWARE_INTERFACE_PUBLIC
90 return_type read(
const rclcpp::Time & time,
const rclcpp::Duration & period);
92 HARDWARE_INTERFACE_PUBLIC
93 return_type write(
const rclcpp::Time & time,
const rclcpp::Duration & period);
96 std::unique_ptr<ActuatorInterface> impl_;