Class Actuator

Class Documentation

class Actuator

Public Functions

Actuator() = default
explicit HARDWARE_INTERFACE_PUBLIC Actuator(std::unique_ptr<ActuatorInterface> impl)
explicit HARDWARE_INTERFACE_PUBLIC Actuator(Actuator &&other) noexcept
~Actuator() = default
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & initialize (const HardwareInfo &actuator_info, rclcpp::Logger logger, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & cleanup ()
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & shutdown ()
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & activate ()
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & deactivate ()
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & error ()
HARDWARE_INTERFACE_PUBLIC std::vector< StateInterface::ConstSharedPtr > export_state_interfaces ()
HARDWARE_INTERFACE_PUBLIC std::vector< CommandInterface::SharedPtr > export_command_interfaces ()
HARDWARE_INTERFACE_PUBLIC return_type prepare_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces)
HARDWARE_INTERFACE_PUBLIC return_type perform_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces)
HARDWARE_INTERFACE_PUBLIC std::string get_name () const
HARDWARE_INTERFACE_PUBLIC std::string get_group_name () const
HARDWARE_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state () const
HARDWARE_INTERFACE_PUBLIC return_type read (const rclcpp::Time &time, const rclcpp::Duration &period)
HARDWARE_INTERFACE_PUBLIC return_type write (const rclcpp::Time &time, const rclcpp::Duration &period)