#include <ign_system_interface.hpp>
|
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 |
|
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 |
|
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) |
|
Definition at line 37 of file ign_system_interface.hpp.
◆ ControlMethod
◆ 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 |
◆ nh_
The documentation for this class was generated from the following file: