ros2_control - humble
|
Public Member Functions | |
RCLCPP_SHARED_PTR_DEFINITIONS (CarlikeBotSystemHardware) | |
hardware_interface::CallbackReturn | on_init (const hardware_interface::HardwareInfo &info) override |
Initialization of the hardware interface from data parsed from the robot's URDF. More... | |
std::vector< hardware_interface::StateInterface > | export_state_interfaces () override |
Exports all state interfaces for this hardware interface. More... | |
std::vector< hardware_interface::CommandInterface > | export_command_interfaces () override |
Exports all command interfaces for this hardware interface. More... | |
hardware_interface::CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
hardware_interface::CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
hardware_interface::return_type | read (const rclcpp::Time &time, const rclcpp::Duration &period) override |
Read the current state values from the actuator. More... | |
hardware_interface::return_type | write (const rclcpp::Time &time, const rclcpp::Duration &period) override |
Write the current command values to the actuator. More... | |
rclcpp::Logger | get_logger () const |
Get the logger of the SystemInterface. More... | |
rclcpp::Clock::SharedPtr | get_clock () const |
Get the clock of the SystemInterface. More... | |
Public Member Functions inherited from hardware_interface::SystemInterface | |
SystemInterface (const SystemInterface &other)=delete | |
SystemInterface copy constructor is actively deleted. More... | |
SystemInterface (SystemInterface &&other)=default | |
virtual return_type | prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
Prepare for a new command interface switch. More... | |
virtual return_type | perform_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &) |
virtual std::string | get_name () const |
Get name of the actuator hardware. More... | |
const rclcpp_lifecycle::State & | get_state () const |
Get life-cycle state of the actuator hardware. More... | |
void | set_state (const rclcpp_lifecycle::State &new_state) |
Set life-cycle state of the actuator hardware. More... | |
Additional Inherited Members | |
Protected Attributes inherited from hardware_interface::SystemInterface | |
HardwareInfo | info_ |
rclcpp_lifecycle::State | lifecycle_state_ |
|
overridevirtual |
Exports all command interfaces for this hardware interface.
The command interfaces have to be created and transferred according to the hardware info passed in for the configuration.
Note the ownership over the state interfaces is transferred to the caller.
Implements hardware_interface::SystemInterface.
|
overridevirtual |
Exports all state interfaces for this hardware interface.
The state interfaces have to be created and transferred according to the hardware info passed in for the configuration.
Note the ownership over the state interfaces is transferred to the caller.
Implements hardware_interface::SystemInterface.
|
inline |
Get the clock of the SystemInterface.
|
inline |
Get the logger of the SystemInterface.
|
overridevirtual |
Initialization of the hardware interface from data parsed from the robot's URDF.
[in] | hardware_info | structure with data from URDF. |
Reimplemented from hardware_interface::SystemInterface.
|
overridevirtual |
Read the current state values from the actuator.
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::SystemInterface.
|
overridevirtual |
Write the current command values to the actuator.
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.