Public Types | Public Member Functions
labust::allocation::AllocationInterface Class Reference

#include <allocation_interface.h>

Inheritance diagram for labust::allocation::AllocationInterface:
Inheritance graph
[legend]

List of all members.

Public Types

enum  {
  X = 0, Y, Z, K,
  M, N
}
 The virtual thrust and torque enumerator. More...
typedef boost::shared_ptr
< AllocationInterface const > 
ConstPtr
 Const pointer typedef.
typedef boost::shared_ptr
< AllocationInterface
Ptr
 Pointer typedef.

Public Member Functions

virtual const std::vector
< double > & 
allocate (const Eigen::VectorXd &tau)=0
 AllocationInterface ()
 Main constructor.
virtual bool configure (ros::NodeHandle &nh, ros::NodeHandle &ph)=0
virtual const Eigen::VectorXd & tauA () const =0
virtual const std::vector< bool > & windup ()=0
virtual ~AllocationInterface ()
 Main destructor.

Detailed Description

Defines a generic allocation interface for all allocation classes to inherit in order to implement a plug-in based allocation.

Definition at line 50 of file allocation_interface.h.


Member Typedef Documentation

Const pointer typedef.

Definition at line 59 of file allocation_interface.h.

Pointer typedef.

Definition at line 57 of file allocation_interface.h.


Member Enumeration Documentation

anonymous enum

The virtual thrust and torque enumerator.

Enumerator:
X 
Y 
Z 
K 
M 
N 

Definition at line 54 of file allocation_interface.h.


Constructor & Destructor Documentation

Main constructor.

Definition at line 62 of file allocation_interface.h.

Main destructor.

Definition at line 64 of file allocation_interface.h.


Member Function Documentation

virtual const std::vector<double>& labust::allocation::AllocationInterface::allocate ( const Eigen::VectorXd &  tau) [pure virtual]

The main allocation function that distributes desired forces and moments directly to the thrusters.

Returns:
Returns the vector of PWM values need to achieve the desired tau

Implemented in labust::allocation::X2dAdaptive.

The main configuration method. The method load parameters and initializes the subscribers and publishers of the allocation.

Implemented in labust::allocation::X2dAdaptive.

virtual const Eigen::VectorXd& labust::allocation::AllocationInterface::tauA ( ) const [pure virtual]

The method returns the last achieved tau vector.

Implemented in labust::allocation::X2dAdaptive.

virtual const std::vector<bool>& labust::allocation::AllocationInterface::windup ( ) [pure virtual]

The method returns the windup flags per degree of freedom.

Implemented in labust::allocation::X2dAdaptive.


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


labust_allocation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:28