![]() |
ros2_control - rolling
|


Public Member Functions | |
| CallbackReturn | on_init (const hardware_interface::HardwareComponentInterfaceParams ¶ms) override |
| Initialization of the hardware interface from data parsed from the robot's URDF. | |
| hardware_interface::CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
| hardware_interface::CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
| std::vector< hardware_interface::InterfaceDescription > | export_unlisted_command_interface_descriptions () override |
| return_type | prepare_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override |
| Prepare for a new command interface switch. | |
| return_type | perform_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override |
| return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period) override |
| Read the current state values from the hardware. | |
| return_type | write (const rclcpp::Time &, const rclcpp::Duration &) override |
| 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 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 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< CommandInterface::SharedPtr > | on_export_command_interfaces () |
| HardwareComponentCycleStatus | trigger_read (const rclcpp::Time &time, const rclcpp::Duration &period) |
| Triggers the read method synchronously or asynchronously depending on the HardwareInfo. | |
| 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. | |
Protected Attributes | |
| const std::vector< std::string > | standard_interfaces_ |
| Use standard interfaces for joints because they are relevant for dynamic behavior. | |
| std::vector< std::string > | skip_interfaces_ |
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_ |
|
overridevirtual |
Override this method to export custom CommandInterfaces which are not defined in the URDF file. Those interfaces will be added to the unlisted_command_interfaces_ map.
Reimplemented from hardware_interface::HardwareComponentInterface.
|
overridevirtual |
Initialization of the hardware interface from data parsed from the robot's URDF.
| [in] | params | A struct of type hardware_interface::HardwareComponentInterfaceParams containing all necessary parameters for initializing this specific hardware component, specifically its HardwareInfo, and a weak_ptr to the executor. |
cancel() or use blocking callbacks such as spin(). Reimplemented from hardware_interface::HardwareComponentInterface.
|
overridevirtual |
Perform the mode-switching for the new command interface combination.
| [in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
| [in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
Reimplemented from hardware_interface::HardwareComponentInterface.
|
overridevirtual |
Prepare for a new command interface switch.
Prepare for any mode-switching required by the new command interface combination.
| [in] | start_interfaces | vector of string identifiers for the command interfaces starting. |
| [in] | stop_interfaces | vector of string identifiers for the command interfaces stopping. |
Reimplemented from hardware_interface::HardwareComponentInterface.
|
overridevirtual |
Read the current state values from the hardware.
The data readings from the physical hardware has to be updated and reflected accordingly in the exported state interfaces. That is, the data pointed by the interfaces shall be updated.
| [in] | time | The time at the start of this control loop iteration |
| [in] | period | The measured time taken by the last control loop iteration |
Implements hardware_interface::HardwareComponentInterface.
|
inlineoverridevirtual |
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 |
Implements hardware_interface::SystemInterface.
|
protected |
Use standard interfaces for joints because they are relevant for dynamic behavior.
By splitting the standard interfaces from other type, the users are able to inherit this class and simply create small "simulation" with desired dynamic behavior. The advantage over using Gazebo is that enables "quick & dirty" tests of robot's URDF and controllers.