Public Types | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
pr2_controller_interface::Controller Class Referenceabstract

#include <controller.h>

Inheritance diagram for pr2_controller_interface::Controller:
Inheritance graph
[legend]

Public Types

enum  { BEFORE_ME, AFTER_ME }
 
enum  { CONSTRUCTED, INITIALIZED, RUNNING }
 
- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 

Public Member Functions

 Controller ()
 
template<class ControllerType >
bool getController (const std::string &name, int sched, ControllerType *&c)
 Method to get access to another controller by name and type. More...
 
virtual bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)=0
 The init function is called to initialize the controller from a non-realtime thread. More...
 
bool initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
bool isRunning ()
 Check if the controller is running. More...
 
virtual void starting ()
 The starting method is called just before the first update from within the realtime thread. More...
 
void starting (const ros::Time &time)
 
bool startRequest ()
 
virtual void stopping ()
 The stopping method is called by the realtime thread just after the last update call. More...
 
void stopping (const ros::Time &time)
 
bool stopRequest ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
virtual void update (void)=0
 The update method is called periodically by the realtime thread when the controller is running. More...
 
void updateRequest ()
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::Controller< pr2_mechanism_model::RobotState >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Public Attributes

std::vector< std::string > after_list_
 
std::vector< std::string > before_list_
 
enum pr2_controller_interface::Controller:: { ... }  state_
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 

Private Member Functions

 Controller (const Controller &c)
 
Controlleroperator= (const Controller &c)
 

Private Attributes

ControllerProvidercontr_prov_
 

Additional Inherited Members

- Protected Member Functions inherited from controller_interface::Controller< pr2_mechanism_model::RobotState >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Detailed Description

Definition at line 53 of file controller.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
BEFORE_ME 
AFTER_ME 

Definition at line 56 of file controller.h.

◆ anonymous enum

anonymous enum
Enumerator
CONSTRUCTED 
INITIALIZED 
RUNNING 

Definition at line 166 of file controller.h.

Constructor & Destructor Documentation

◆ Controller() [1/2]

pr2_controller_interface::Controller::Controller ( )
inline

Definition at line 58 of file controller.h.

◆ ~Controller()

virtual pr2_controller_interface::Controller::~Controller ( )
inlinevirtual

Definition at line 59 of file controller.h.

◆ Controller() [2/2]

pr2_controller_interface::Controller::Controller ( const Controller c)
private

Member Function Documentation

◆ getController()

template<class ControllerType >
bool pr2_controller_interface::Controller::getController ( const std::string &  name,
int  sched,
ControllerType *&  c 
)
inline

Method to get access to another controller by name and type.

Definition at line 90 of file controller.h.

◆ init()

virtual bool pr2_controller_interface::Controller::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
pure virtual

The init function is called to initialize the controller from a non-realtime thread.

Parameters
robotA RobotState object which can be used to read joint states and write out effort commands.
nA NodeHandle in the namespace from which the controller should read its configuration, and where it should set up its ROS interface.
Returns
True if initialization was successful and the controller is ready to be started.

◆ initRequest()

bool pr2_controller_interface::Controller::initRequest ( ControllerProvider cp,
pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
inline

Definition at line 146 of file controller.h.

◆ isRunning()

bool pr2_controller_interface::Controller::isRunning ( )
inline

Check if the controller is running.

Definition at line 110 of file controller.h.

◆ operator=()

Controller& pr2_controller_interface::Controller::operator= ( const Controller c)
private

◆ starting() [1/2]

virtual void pr2_controller_interface::Controller::starting ( )
inlinevirtual

The starting method is called just before the first update from within the realtime thread.

Definition at line 66 of file controller.h.

◆ starting() [2/2]

void pr2_controller_interface::Controller::starting ( const ros::Time time)
inlinevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 61 of file controller.h.

◆ startRequest()

bool pr2_controller_interface::Controller::startRequest ( )
inline

Definition at line 121 of file controller.h.

◆ stopping() [1/2]

virtual void pr2_controller_interface::Controller::stopping ( )
inlinevirtual

The stopping method is called by the realtime thread just after the last update call.

Definition at line 72 of file controller.h.

◆ stopping() [2/2]

void pr2_controller_interface::Controller::stopping ( const ros::Time time)
inlinevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 63 of file controller.h.

◆ stopRequest()

bool pr2_controller_interface::Controller::stopRequest ( )
inline

Definition at line 134 of file controller.h.

◆ update() [1/2]

void pr2_controller_interface::Controller::update ( const ros::Time time,
const ros::Duration period 
)
inlinevirtual

Implements controller_interface::ControllerBase.

Definition at line 62 of file controller.h.

◆ update() [2/2]

virtual void pr2_controller_interface::Controller::update ( void  )
pure virtual

The update method is called periodically by the realtime thread when the controller is running.

◆ updateRequest()

void pr2_controller_interface::Controller::updateRequest ( )
inline

Definition at line 115 of file controller.h.

Member Data Documentation

◆ after_list_

std::vector<std::string> pr2_controller_interface::Controller::after_list_

Definition at line 164 of file controller.h.

◆ before_list_

std::vector<std::string> pr2_controller_interface::Controller::before_list_

Definition at line 164 of file controller.h.

◆ contr_prov_

ControllerProvider* pr2_controller_interface::Controller::contr_prov_
private

Definition at line 171 of file controller.h.

◆ state_

enum { ... } pr2_controller_interface::Controller::state_

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


pr2_controller_interface
Author(s): Wim Meeussen
autogenerated on Mon Mar 6 2023 03:49:18