ros2_control - humble
Public Member Functions | List of all members
ign_ros2_control::IgnitionSystem Class Reference
Inheritance diagram for ign_ros2_control::IgnitionSystem:
Inheritance graph
[legend]
Collaboration diagram for ign_ros2_control::IgnitionSystem:
Collaboration graph
[legend]

Public Member Functions

CallbackReturn on_init (const hardware_interface::HardwareInfo &system_info) override
 Initialization of the hardware interface from data parsed from the robot's URDF. More...
 
CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 
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...
 
CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
 
CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
 
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 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...
 
bool initSim (rclcpp::Node::SharedPtr &model_nh, std::map< std::string, ignition::gazebo::Entity > &joints, const hardware_interface::HardwareInfo &hardware_info, ignition::gazebo::EntityComponentManager &_ecm, int &update_rate) override
 Initialize the system interface param[in] model_nh Pointer to the ros2 node param[in] joints Map with the name of the joint as the key and the value is related with the entity in Gazebo param[in] hardware_info structure with data from URDF. param[in] _ecm Entity-component manager. param[in] update_rate controller update rate.
 
- 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 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

- Public Types inherited from ign_ros2_control::IgnitionSystemInterface
enum  ControlMethod_ { NONE = 0 , POSITION = (1 << 0) , VELOCITY = (1 << 1) , EFFORT = (1 << 2) }
 
typedef SafeEnum< enum ControlMethod_ > ControlMethod
 
- Protected Attributes inherited from ign_ros2_control::IgnitionSystemInterface
rclcpp::Node::SharedPtr nh_
 
- 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 > ign_ros2_control::IgnitionSystem::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 > ign_ros2_control::IgnitionSystem::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 ign_ros2_control::IgnitionSystem::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()

hardware_interface::return_type ign_ros2_control::IgnitionSystem::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.

◆ read()

hardware_interface::return_type ign_ros2_control::IgnitionSystem::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()

hardware_interface::return_type ign_ros2_control::IgnitionSystem::write ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
overridevirtual

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.


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