Public Types | Public Member Functions | Protected Attributes | List of all members
ign_ros_control::IgnitionSystemInterface Class Referenceabstract

#include <ign_system_interface.hpp>

Inheritance diagram for ign_ros_control::IgnitionSystemInterface:
Inheritance graph
[legend]

Public Types

enum  ControlMethod {
  EFFORT, POSITION, POSITION_PID, VELOCITY,
  VELOCITY_PID
}
 
- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR }
 

Public Member Functions

virtual bool initSim (ros::NodeHandle model_nh, std::map< std::string, ignition::gazebo::Entity > &joints, ignition::gazebo::EntityComponentManager &_ecm, std::vector< transmission_interface::TransmissionInfo > transmissions, int &update_rate)=0
 Initialize the system interface param[in] model_nh Pointer to the ros 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] _ecm Entity-component manager. param[in] transmissions structure to handle joint with transmissions param[in] update_rate controller update rate. More...
 
virtual void read ()=0
 
virtual void write ()=0
 
- Public Member Functions inherited from hardware_interface::RobotHW
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual bool init (ros::NodeHandle &, ros::NodeHandle &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual SwitchState switchResult () const
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual ~RobotHW ()=default
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
T * get ()
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 
std::vector< std::string > getNames () const
 
void registerInterface (T *iface)
 
void registerInterfaceManager (InterfaceManager *iface_man)
 

Protected Attributes

ros::NodeHandle nh_
 
- Protected Attributes inherited from hardware_interface::InterfaceManager
std::vector< ResourceManagerBase * > interface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Additional Inherited Members

- Protected Types inherited from hardware_interface::InterfaceManager
typedef std::vector< InterfaceManager * > InterfaceManagerVector
 
typedef std::map< std::string, void * > InterfaceMap
 
typedef std::map< std::string, std::vector< std::string > > ResourceMap
 
typedef std::map< std::string, size_t > SizeMap
 

Detailed Description

Definition at line 37 of file ign_system_interface.hpp.

Member Enumeration Documentation

◆ ControlMethod

Enumerator
EFFORT 
POSITION 
POSITION_PID 
VELOCITY 
VELOCITY_PID 

Definition at line 57 of file ign_system_interface.hpp.

Member Function Documentation

◆ initSim()

virtual bool ign_ros_control::IgnitionSystemInterface::initSim ( ros::NodeHandle  model_nh,
std::map< std::string, ignition::gazebo::Entity > &  joints,
ignition::gazebo::EntityComponentManager &  _ecm,
std::vector< transmission_interface::TransmissionInfo transmissions,
int &  update_rate 
)
pure virtual

Initialize the system interface param[in] model_nh Pointer to the ros 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] _ecm Entity-component manager. param[in] transmissions structure to handle joint with transmissions param[in] update_rate controller update rate.

Implemented in ign_ros_control::IgnitionSystem.

◆ read()

virtual void ign_ros_control::IgnitionSystemInterface::read ( )
pure virtual

◆ write()

virtual void ign_ros_control::IgnitionSystemInterface::write ( )
pure virtual

Member Data Documentation

◆ nh_

ros::NodeHandle ign_ros_control::IgnitionSystemInterface::nh_
protected

Definition at line 67 of file ign_system_interface.hpp.


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


ign_ros_control
Author(s): Gennaro Raiola
autogenerated on Sun Aug 14 2022 02:23:53