ros2_control - galactic
|
Classes | |
struct | MimicJoint |
Public Member Functions | |
CallbackReturn | on_init (const hardware_interface::HardwareInfo &info) override |
Initialization of the hardware interface from data parsed from the robot's URDF. | |
std::vector< hardware_interface::StateInterface > | export_state_interfaces () override |
Exports all state interfaces for this hardware interface. | |
std::vector< hardware_interface::CommandInterface > | export_command_interfaces () override |
Exports all command interfaces for this hardware interface. | |
return_type | read () override |
Read the current state values from the actuator. | |
return_type | write () override |
Write the current command values to the actuator. | |
Public Member Functions inherited from hardware_interface::SystemInterface | |
SystemInterface (const SystemInterface &other)=delete | |
SensorInterface copy constructor is actively deleted. | |
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. | |
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. | |
const rclcpp_lifecycle::State & | get_state () const |
Get life-cycle state of the actuator hardware. | |
void | set_state (const rclcpp_lifecycle::State &new_state) |
Set life-cycle state of the actuator hardware. | |
Protected Attributes | |
const std::vector< std::string > | standard_interfaces_ |
Use standard interfaces for joints because they are relevant for dynamic behavior. | |
const size_t | POSITION_INTERFACE_INDEX = 0 |
std::vector< MimicJoint > | mimic_joints_ |
std::vector< std::vector< double > > | joint_commands_ |
The size of this vector is (standard_interfaces_.size() x nr_joints) | |
std::vector< std::vector< double > > | joint_states_ |
std::vector< std::string > | other_interfaces_ |
std::vector< std::vector< double > > | other_commands_ |
The size of this vector is (other_interfaces_.size() x nr_joints) | |
std::vector< std::vector< double > > | other_states_ |
std::vector< std::string > | sensor_interfaces_ |
std::vector< std::vector< double > > | sensor_fake_commands_ |
The size of this vector is (sensor_interfaces_.size() x nr_joints) | |
std::vector< std::vector< double > > | sensor_states_ |
std::vector< std::string > | gpio_interfaces_ |
std::vector< std::vector< double > > | gpio_fake_commands_ |
The size of this vector is (gpio_interfaces_.size() x nr_joints) | |
std::vector< std::vector< double > > | gpio_commands_ |
std::vector< std::vector< double > > | gpio_states_ |
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.
|
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.
Implements hardware_interface::SystemInterface.
|
inlineoverridevirtual |
Write the current command values to the actuator.
The physical hardware shall be updated with the latest value from the exported command interfaces.
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.