ROS2 Control
|
Classes | |
struct | MimicJoint |
Public Member Functions | |
return_type | configure (const hardware_interface::HardwareInfo &info) override |
Configuration of the system from data parsed from the robot's URDF. More... | |
std::vector< hardware_interface::StateInterface > | export_state_interfaces () override |
Exports all state interfaces for this system. More... | |
std::vector< hardware_interface::CommandInterface > | export_command_interfaces () override |
Exports all command interfaces for this system. More... | |
return_type | start () override |
Start exchange data with the hardware. More... | |
return_type | stop () override |
Stop exchange data with the hardware. More... | |
return_type | read () override |
Read the current state values from the actuators and sensors within the system. More... | |
return_type | write () override |
Write the current command values to the actuator within the system. More... | |
![]() | |
return_type | configure (const HardwareInfo &info) override |
return_type | configure_default (const HardwareInfo &info) |
std::string | get_name () const final |
status | get_status () const final |
![]() | |
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 > &) |
Protected Attributes | |
const std::vector< std::string > | standard_interfaces_ |
Use standard interfaces for joints because they are relevant for dynamic behaviour. More... | |
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 (other_interfaces_.size() x nr_joints) | |
std::vector< std::vector< double > > | sensor_states_ |
![]() | |
HardwareInfo | info_ |
status | status_ |
|
overridevirtual |
Configuration of the system from data parsed from the robot's URDF.
[in] | system_info | structure with data from URDF. |
Implements hardware_interface::SystemInterface.
|
overridevirtual |
Exports all command interfaces for this system.
The command interfaces have to be created and transferred according to the system 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 system.
The state interfaces have to be created and transferred according to the system info passed in for the configuration.
Note the ownership over the state interfaces is transferred to the caller.
Implements hardware_interface::SystemInterface.
|
overridevirtual |
Read the current state values from the actuators and sensors within the system.
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 |
Start exchange data with the hardware.
Implements hardware_interface::SystemInterface.
|
inlineoverridevirtual |
Stop exchange data with the hardware.
Implements hardware_interface::SystemInterface.
|
inlineoverridevirtual |
Write the current command values to the actuator within the system.
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 behaviour.
By splitting the standard interfaces from other type, the users are able to inherit this class and simply create small "simulation" with desired dynamic behaviour. The advantage over using Gazebo is that enables "quick & dirty" tests of robot's URDF and controllers.