ros2_control - foxy
Loading...
Searching...
No Matches
Public Member Functions | List of all members
gazebo_ros2_control::GazeboSystem Class Reference
Inheritance diagram for gazebo_ros2_control::GazeboSystem:
Inheritance graph
[legend]
Collaboration diagram for gazebo_ros2_control::GazeboSystem:
Collaboration graph
[legend]

Public Member Functions

hardware_interface::return_type configure (const hardware_interface::HardwareInfo &system_info) override
 Configuration of the system from data parsed from the robot's URDF.
 
std::vector< hardware_interface::StateInterfaceexport_state_interfaces () override
 Exports all state interfaces for this system.
 
std::vector< hardware_interface::CommandInterfaceexport_command_interfaces () override
 Exports all command interfaces for this system.
 
hardware_interface::return_type start () override
 Start exchange data with the hardware.
 
hardware_interface::return_type stop () override
 Stop exchange data with the hardware.
 
hardware_interface::return_type read () override
 Read the current state values from the actuators and sensors within the system.
 
hardware_interface::return_type perform_command_mode_switch (const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
 
hardware_interface::return_type write () override
 Write the current command values to the actuator within the system.
 
bool initSim (rclcpp::Node::SharedPtr &model_nh, gazebo::physics::ModelPtr parent_model, const hardware_interface::HardwareInfo &hardware_info, sdf::ElementPtr sdf) override
 Initialize the system interface param[in] model_nh pointer to the ros2 node param[in] parent_model pointer to the model param[in] control_hardware vector filled with information about robot's control resources param[in] sdf pointer to the SDF.
 
- Public Member Functions inherited from hardware_interface::BaseInterface< hardware_interface::SystemInterface >
return_type configure_default (const HardwareInfo &info)
 
std::string get_name () const final
 
status get_status () const final
 
- Public Member Functions inherited from hardware_interface::SystemInterface
virtual return_type prepare_command_mode_switch (const std::vector< std::string > &, const std::vector< std::string > &)
 Prepare for a new command interface switch.
 

Additional Inherited Members

- Public Types inherited from gazebo_ros2_control::GazeboSystemInterface
enum  ControlMethod_ { NONE = 0 , POSITION = (1 << 0) , VELOCITY = (1 << 1) , EFFORT = (1 << 2) }
 
typedef SafeEnum< enum ControlMethod_ > ControlMethod
 
- Protected Attributes inherited from gazebo_ros2_control::GazeboSystemInterface
rclcpp::Node::SharedPtr nh_
 
- Protected Attributes inherited from hardware_interface::BaseInterface< hardware_interface::SystemInterface >
HardwareInfo info_
 
status status_
 

Member Function Documentation

◆ configure()

hardware_interface::return_type gazebo_ros2_control::GazeboSystem::configure ( const hardware_interface::HardwareInfo system_info)
overridevirtual

Configuration of the system from data parsed from the robot's URDF.

Parameters
[in]system_infostructure with data from URDF.
Returns
return_type::OK if required data are provided and can be parsed, return_type::ERROR otherwise.

Reimplemented from hardware_interface::BaseInterface< hardware_interface::SystemInterface >.

◆ export_command_interfaces()

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

Returns
vector of command interfaces

Implements hardware_interface::SystemInterface.

◆ export_state_interfaces()

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

Returns
vector of state interfaces

Implements hardware_interface::SystemInterface.

◆ initSim()

bool gazebo_ros2_control::GazeboSystem::initSim ( rclcpp::Node::SharedPtr &  model_nh,
gazebo::physics::ModelPtr  parent_model,
const hardware_interface::HardwareInfo hardware_info,
sdf::ElementPtr  sdf 
)
overridevirtual

Initialize the system interface param[in] model_nh pointer to the ros2 node param[in] parent_model pointer to the model param[in] control_hardware vector filled with information about robot's control resources param[in] sdf pointer to the SDF.

Implements gazebo_ros2_control::GazeboSystemInterface.

◆ perform_command_mode_switch()

hardware_interface::return_type gazebo_ros2_control::GazeboSystem::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 interfacs 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.

◆ read()

hardware_interface::return_type gazebo_ros2_control::GazeboSystem::read ( )
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.

Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.

◆ start()

hardware_interface::return_type gazebo_ros2_control::GazeboSystem::start ( )
overridevirtual

Start exchange data with the hardware.

Returns
return_type:OK if everything worked as expected, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.

◆ stop()

hardware_interface::return_type gazebo_ros2_control::GazeboSystem::stop ( )
overridevirtual

Stop exchange data with the hardware.

Returns
return_type:OK if everything worked as expected, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.

◆ write()

hardware_interface::return_type gazebo_ros2_control::GazeboSystem::write ( )
overridevirtual

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.

Returns
return_type::OK if the read was successful, return_type::ERROR otherwise.

Implements hardware_interface::SystemInterface.


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