![]() |
ros2_control - kilted
|
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control. More...
#include <actuator_interface.hpp>


Public Member Functions | |
| return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period) override=0 |
| Write the current command values to the hardware. | |
Public Member Functions inherited from hardware_interface::HardwareComponentInterface | |
| HardwareComponentInterface (const HardwareComponentInterface &other)=delete | |
| HardwareComponentInterface copy constructor is actively deleted. | |
| HardwareComponentInterface (HardwareComponentInterface &&other)=delete | |
| CallbackReturn | init (const HardwareInfo &hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock) |
| CallbackReturn | init (const hardware_interface::HardwareComponentParams ¶ms) |
| virtual CallbackReturn | init_hardware_status_message (control_msgs::msg::HardwareStatus &) |
| User-overridable method to configure the structure of the HardwareStatus message. | |
| virtual return_type | update_hardware_status_message (control_msgs::msg::HardwareStatus &) |
| User-overridable method to fill the hardware status message with real-time data. | |
| virtual CallbackReturn | on_init (const HardwareInfo &hardware_info) |
| Initialization of the hardware interface from data parsed from the robot's URDF. | |
| virtual CallbackReturn | on_init (const hardware_interface::HardwareComponentInterfaceParams ¶ms) |
| Initialization of the hardware interface from data parsed from the robot's URDF. | |
| virtual std::vector< StateInterface > | export_state_interfaces () |
| Exports all state interfaces for this hardware interface. | |
| virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_state_interface_descriptions () |
| virtual std::vector< StateInterface::ConstSharedPtr > | on_export_state_interfaces () |
| virtual std::vector< CommandInterface > | export_command_interfaces () |
| Exports all command interfaces for this hardware interface. | |
| virtual std::vector< hardware_interface::InterfaceDescription > | export_unlisted_command_interface_descriptions () |
| virtual std::vector< CommandInterface::SharedPtr > | on_export_command_interfaces () |
| virtual return_type | prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
| Prepare for a new command interface switch. | |
| virtual return_type | perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
| HardwareComponentCycleStatus | trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period) |
| Triggers the read method synchronously or asynchronously depending on the HardwareInfo. | |
| virtual return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
| Read the current state values from the hardware. | |
| HardwareComponentCycleStatus | trigger_write (const rclcpp::Time &time, const rclcpp::Duration &period) |
| Triggers the write method synchronously or asynchronously depending on the HardwareInfo. | |
| const std::string & | get_name () const |
| Get name of the hardware. | |
| const std::string & | get_group_name () const |
| Get name of the hardware group to which it belongs to. | |
| const rclcpp_lifecycle::State & | get_lifecycle_state () const |
| Get life-cycle state of the hardware. | |
| void | set_lifecycle_state (const rclcpp_lifecycle::State &new_state) |
| Set life-cycle state of the hardware. | |
| bool | has_state (const std::string &interface_name) const |
| Does the state interface exist? | |
| template<typename T > | |
| void | set_state (const std::string &interface_name, const T &value) |
| Set the value of a state interface. | |
| template<typename T = double> | |
| T | get_state (const std::string &interface_name) const |
| Get the value from a state interface. | |
| bool | has_command (const std::string &interface_name) const |
| Does the command interface exist? | |
| template<typename T > | |
| void | set_command (const std::string &interface_name, const T &value) |
| Set the value of a command interface. | |
| template<typename T = double> | |
| T | get_command (const std::string &interface_name) const |
| Get the value from a command interface. | |
| rclcpp::Logger | get_logger () const |
| Get the logger of the HardwareComponentInterface. | |
| rclcpp::Clock::SharedPtr | get_clock () const |
| Get the clock. | |
| rclcpp::Node::SharedPtr | get_node () const |
| Get the default node of the HardwareComponentInterface. | |
| const HardwareInfo & | get_hardware_info () const |
| Get the hardware info of the HardwareComponentInterface. | |
| void | pause_async_operations () |
| Pause any asynchronous operations. | |
| void | prepare_for_activation () |
| Prepare for the activation of the hardware. | |
| void | enable_introspection (bool enable) |
| Enable or disable introspection of the hardware. | |
Additional Inherited Members | |
Protected Attributes inherited from hardware_interface::HardwareComponentInterface | |
| HardwareInfo | info_ |
| std::unordered_map< std::string, InterfaceDescription > | joint_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | joint_command_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | sensor_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | gpio_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | gpio_command_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | unlisted_state_interfaces_ |
| std::unordered_map< std::string, InterfaceDescription > | unlisted_command_interfaces_ |
| rclcpp_lifecycle::State | lifecycle_state_ |
| std::unique_ptr< realtime_tools::AsyncFunctionHandler< return_type > > | async_handler_ |
| std::vector< StateInterface::SharedPtr > | joint_states_ |
| std::vector< CommandInterface::SharedPtr > | joint_commands_ |
| std::vector< StateInterface::SharedPtr > | sensor_states_ |
| std::vector< StateInterface::SharedPtr > | gpio_states_ |
| std::vector< CommandInterface::SharedPtr > | gpio_commands_ |
| std::vector< StateInterface::SharedPtr > | unlisted_states_ |
| std::vector< CommandInterface::SharedPtr > | unlisted_commands_ |
| pal_statistics::RegistrationsRAII | stats_registrations_ |
| std::shared_ptr< rclcpp::Publisher< control_msgs::msg::HardwareStatus > > | hardware_status_publisher_ |
| realtime_tools::RealtimeThreadSafeBox< std::optional< control_msgs::msg::HardwareStatus > > | hardware_status_box_ |
| rclcpp::TimerBase::SharedPtr | hardware_status_timer_ |
Virtual Class to implement when integrating a 1 DoF actuator into ros2_control.
The typical examples are conveyors or motors.
Methods return values have type rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn with the following meaning:
The hardware ends after each method in a state with the following meaning:
UNCONFIGURED (on_init, on_cleanup): Hardware is initialized but communication is not started and therefore no interface is available.
INACTIVE (on_configure, on_deactivate): Communication with the hardware is started and it is configured. States can be read, but command interfaces are not available.
FINALIZED (on_shutdown): Hardware interface is ready for unloading/destruction. Allocated memory is cleaned up.
ACTIVE (on_activate): Power circuits of hardware are active and hardware can be moved, e.g., brakes are disabled. Command interfaces are available.
|
overridepure virtual |
Write the current command values to the hardware.
The physical hardware shall be updated with the latest value from the exported command interfaces.
| [in] | time | The time at the start of this control loop iteration |
| [in] | period | The measured time taken by the last control loop iteration |
Reimplemented from hardware_interface::HardwareComponentInterface.
Implemented in ros2_control_demo_example_14::RRBotActuatorWithoutFeedback, and ros2_control_demo_example_6::RRBotModularJoint.