Abstract Controller Interface.  
 More...
#include <controller_base.h>
Abstract Controller Interface. 
Definition at line 48 of file controller_base.h.
◆ ClaimedResources
◆ ControllerState
| Enumerator | 
|---|
| CONSTRUCTED |  | 
| INITIALIZED |  | 
| RUNNING |  | 
| STOPPED |  | 
| WAITING |  | 
| ABORTED |  | 
Definition at line 243 of file controller_base.h.
 
 
◆ ControllerBase() [1/3]
  
  | 
        
          | controller_interface::ControllerBase::ControllerBase | ( |  | ) |  |  | default | 
 
 
◆ ~ControllerBase()
  
  | 
        
          | virtual controller_interface::ControllerBase::~ControllerBase | ( |  | ) |  |  | virtualdefault | 
 
 
◆ ControllerBase() [2/3]
  
  | 
        
          | controller_interface::ControllerBase::ControllerBase | ( | const ControllerBase & |  | ) |  |  | delete | 
 
 
◆ ControllerBase() [3/3]
  
  | 
        
          | controller_interface::ControllerBase::ControllerBase | ( | ControllerBase && |  | ) |  |  | delete | 
 
 
◆ aborting()
  
  | 
        
          | virtual void controller_interface::ControllerBase::aborting | ( | const ros::Time & |  | ) |  |  | inlinevirtual | 
 
This is called from within the realtime thread when the controller needs to be aborted. 
- Parameters
- 
  
  
Definition at line 94 of file controller_base.h.
 
 
◆ abortRequest()
  
  | 
        
          | bool controller_interface::ControllerBase::abortRequest | ( | const ros::Time & | time | ) |  |  | inline | 
 
Calls abort unless this controller is just constructed. 
Definition at line 197 of file controller_base.h.
 
 
◆ initRequest()
Request that the controller be initialized. 
- Parameters
- 
  
    |  | robot_hw | The robot hardware abstraction. |  |  | root_nh | A NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services). |  |  | controller_nh | A NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides. |  | [out] | claimed_resources | The resources claimed by this controller. They can belong to multiple hardware interfaces. |  
 
- Returns
- True if initialization was successful and the controller is ready to be started. 
Implemented in controller_interface::MultiInterfaceController< T >, and controller_interface::Controller< T >.
 
 
◆ isAborted()
  
  | 
        
          | bool controller_interface::ControllerBase::isAborted | ( |  | ) | const |  | inline | 
 
Check if the controller is aborted. 
- Returns
- true if the controller is aborted 
Definition at line 131 of file controller_base.h.
 
 
◆ isInitialized()
  
  | 
        
          | bool controller_interface::ControllerBase::isInitialized | ( |  | ) | const |  | inline | 
 
Check if the controller is initialized. 
- Returns
- true if the controller is initialized 
Definition at line 99 of file controller_base.h.
 
 
◆ isRunning()
  
  | 
        
          | bool controller_interface::ControllerBase::isRunning | ( |  | ) | const |  | inline | 
 
Check if the controller is running. 
- Returns
- true if the controller is running 
Definition at line 107 of file controller_base.h.
 
 
◆ isStopped()
  
  | 
        
          | bool controller_interface::ControllerBase::isStopped | ( |  | ) | const |  | inline | 
 
Check if the controller is stopped. 
- Returns
- true if the controller is stopped 
Definition at line 115 of file controller_base.h.
 
 
◆ isWaiting()
  
  | 
        
          | bool controller_interface::ControllerBase::isWaiting | ( |  | ) | const |  | inline | 
 
Check if the controller is waiting. 
- Returns
- true if the controller is waiting 
Definition at line 123 of file controller_base.h.
 
 
◆ operator=() [1/2]
◆ operator=() [2/2]
◆ starting()
  
  | 
        
          | virtual void controller_interface::ControllerBase::starting | ( | const ros::Time & |  | ) |  |  | inlinevirtual | 
 
This is called from within the realtime thread just before the first call to update. 
- Parameters
- 
  
  
Definition at line 66 of file controller_base.h.
 
 
◆ startRequest()
  
  | 
        
          | bool controller_interface::ControllerBase::startRequest | ( | const ros::Time & | time | ) |  |  | inline | 
 
 
◆ stopping()
  
  | 
        
          | virtual void controller_interface::ControllerBase::stopping | ( | const ros::Time & |  | ) |  |  | inlinevirtual | 
 
This is called from within the realtime thread just after the last update call before the controller is stopped. 
- Parameters
- 
  
  
Definition at line 80 of file controller_base.h.
 
 
◆ stopRequest()
  
  | 
        
          | bool controller_interface::ControllerBase::stopRequest | ( | const ros::Time & | time | ) |  |  | inline | 
 
 
◆ update()
  
  | 
        
          | virtual void controller_interface::ControllerBase::update | ( | const ros::Time & | time, |  
          |  |  | const ros::Duration & | period |  
          |  | ) |  |  |  | pure virtual | 
 
This is called periodically by the realtime thread when the controller is running. 
- Parameters
- 
  
    | time | The current time |  | period | The time passed since the last call to update |  
 
 
 
◆ updateRequest()
  
  | 
        
          | void controller_interface::ControllerBase::updateRequest | ( | const ros::Time & | time, |  
          |  |  | const ros::Duration & | period |  
          |  | ) |  |  |  | inline | 
 
 
◆ waiting()
  
  | 
        
          | virtual void controller_interface::ControllerBase::waiting | ( | const ros::Time & |  | ) |  |  | inlinevirtual | 
 
This is called from within the realtime thread while the controller is waiting to start. 
- Parameters
- 
  
  
Definition at line 87 of file controller_base.h.
 
 
◆ waitRequest()
  
  | 
        
          | bool controller_interface::ControllerBase::waitRequest | ( | const ros::Time & | time | ) |  |  | inline | 
 
 
◆ state_
The documentation for this class was generated from the following file: