ros2_control - humble
Classes | Public Member Functions | Protected Attributes | List of all members
mock_components::GenericSystem Class Reference
Inheritance diagram for mock_components::GenericSystem:
Inheritance graph
[legend]
Collaboration diagram for mock_components::GenericSystem:
Collaboration graph
[legend]

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. More...
 
std::vector< hardware_interface::StateInterfaceexport_state_interfaces () override
 Exports all state interfaces for this hardware interface. More...
 
std::vector< hardware_interface::CommandInterfaceexport_command_interfaces () override
 Exports all command interfaces for this hardware interface. More...
 
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. More...
 
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 actuator. More...
 
return_type write (const rclcpp::Time &, const rclcpp::Duration &) override
 Write the current command values to the actuator. 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 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...
 

Protected Attributes

const std::vector< std::string > standard_interfaces_
 Use standard interfaces for joints because they are relevant for dynamic behavior. More...
 
std::vector< MimicJointmimic_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_mock_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_mock_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_
 

Member Function Documentation

◆ export_command_interfaces()

std::vector< hardware_interface::CommandInterface > mock_components::GenericSystem::export_command_interfaces ( )
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.

Returns
vector of command interfaces

Implements hardware_interface::SystemInterface.

◆ export_state_interfaces()

std::vector< hardware_interface::StateInterface > mock_components::GenericSystem::export_state_interfaces ( )
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.

Returns
vector of state interfaces

Implements hardware_interface::SystemInterface.

◆ on_init()

CallbackReturn mock_components::GenericSystem::on_init ( const hardware_interface::HardwareInfo hardware_info)
overridevirtual

Initialization of the hardware interface from data parsed from the robot's URDF.

Parameters
[in]hardware_infostructure with data from URDF.
Returns
CallbackReturn::SUCCESS if required data are provided and can be parsed.
CallbackReturn::ERROR if any error happens or data are missing.

Reimplemented from hardware_interface::SystemInterface.

◆ perform_command_mode_switch()

return_type mock_components::GenericSystem::perform_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
overridevirtual

Perform the mode-switching for the new command interface combination.

Note
This is part of the realtime update loop, and should be fast.
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be switched to, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

Reimplemented from hardware_interface::SystemInterface.

◆ prepare_command_mode_switch()

return_type mock_components::GenericSystem::prepare_command_mode_switch ( const std::vector< std::string > &  ,
const std::vector< std::string > &   
)
overridevirtual

Prepare for a new command interface switch.

Prepare for any mode-switching required by the new command interface combination.

Note
This is a non-realtime evaluation of whether a set of command interface claims are possible, and call to start preparing data structures for the upcoming switch that will occur.
All starting and stopping interface keys are passed to all components, so the function should return return_type::OK by default when given interface keys not relevant for this component.
Parameters
[in]start_interfacesvector of string identifiers for the command interfaces starting.
[in]stop_interfacesvector of string identifiers for the command interfaces stopping.
Returns
return_type::OK if the new command interface combination can be prepared, or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.

Reimplemented from hardware_interface::SystemInterface.

◆ read()

return_type mock_components::GenericSystem::read ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
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.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.

◆ write()

return_type mock_components::GenericSystem::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
inlineoverridevirtual

Write the current command values to the actuator.

The physical hardware shall be updated with the latest value from the exported command interfaces.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.

Member Data Documentation

◆ standard_interfaces_

const std::vector<std::string> mock_components::GenericSystem::standard_interfaces_
protected
Initial value:
= {
constexpr char HW_IF_EFFORT[]
Constant defining effort interface.
Definition: hardware_interface_type_values.hpp:27
constexpr char HW_IF_ACCELERATION[]
Constant defining acceleration interface.
Definition: hardware_interface_type_values.hpp:25
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition: hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition: hardware_interface_type_values.hpp:21

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.


The documentation for this class was generated from the following files: