Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
labust::vehicles::ThrustAllocator Class Reference

#include <ThrustAllocation.hpp>

List of all members.

Public Member Functions

void allocate (const labust::simulation::vector &tauIn, labust::simulation::vector &tauOut)
const Eigen::VectorXi & getCoercion ()
const Eigen::VectorXd & getThrusterForces ()
template<class AllocMatrix , class DOFMatrix , class ThrusterGroups >
void init (int alloc_type, const AllocMatrix &alloc, const DOFMatrix &use_dofs, const ThrusterGroups &thrust_groups)
void setThrusterMinMax (double min, double max)
 ThrustAllocator ()

Protected Member Functions

void scale_alloc ()
void simple_alloc ()

Protected Attributes

Eigen::MatrixXd B
Eigen::MatrixXd Binv
Eigen::VectorXi coercion
std::vector< int > dofs
std::vector< double > group_scales
std::vector< std::vector< int > > groups
int num_thrusters
Eigen::VectorXd tdes
double tmax
double tmin
int type

Private Types

enum  { NoAlloc = 0, SimpleAlloc = 1, ScaleAlloc = 2 }

Detailed Description

Performs thrust allocation based on configuration. Added support for thruster grouping to support multi-scaling allocation.

Todo:

Add ability to register an external allocation algorithm when the need arises

Is it better to have a bunch of preprogramed simple allocation types that have static alllocation data ?

Split into a compilable cpp when more than one larger class exists for vehicle support

Remove the ROS_ERROR debug messages and any ROS dependencies

Add the windup indication for groups of scaled allocations

Definition at line 59 of file ThrustAllocation.hpp.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
NoAlloc 
SimpleAlloc 
ScaleAlloc 

Definition at line 61 of file ThrustAllocation.hpp.


Constructor & Destructor Documentation

Main constructor.

Definition at line 66 of file ThrustAllocation.hpp.


Member Function Documentation

Performs allocation and necessary conversions.

Definition at line 80 of file ThrustAllocation.hpp.

const Eigen::VectorXi& labust::vehicles::ThrustAllocator::getCoercion ( ) [inline]

Definition at line 218 of file ThrustAllocation.hpp.

const Eigen::VectorXd& labust::vehicles::ThrustAllocator::getThrusterForces ( ) [inline]

Definition at line 216 of file ThrustAllocation.hpp.

template<class AllocMatrix , class DOFMatrix , class ThrusterGroups >
void labust::vehicles::ThrustAllocator::init ( int  alloc_type,
const AllocMatrix &  alloc,
const DOFMatrix &  use_dofs,
const ThrusterGroups &  thrust_groups 
) [inline]

Definition at line 156 of file ThrustAllocation.hpp.

void labust::vehicles::ThrustAllocator::scale_alloc ( ) [inline, protected]

Do scaled allocation.

Definition at line 235 of file ThrustAllocation.hpp.

void labust::vehicles::ThrustAllocator::setThrusterMinMax ( double  min,
double  max 
) [inline]

The method sets the thruster maximum and minimum force.

Definition at line 210 of file ThrustAllocation.hpp.

Do simple allocation.

Definition at line 224 of file ThrustAllocation.hpp.


Member Data Documentation

Eigen::MatrixXd labust::vehicles::ThrustAllocator::B [protected]

The allocation matrix.

Definition at line 278 of file ThrustAllocation.hpp.

Eigen::MatrixXd labust::vehicles::ThrustAllocator::Binv [protected]

Definition at line 278 of file ThrustAllocation.hpp.

Eigen::VectorXi labust::vehicles::ThrustAllocator::coercion [protected]

The coercion vector.

Definition at line 290 of file ThrustAllocation.hpp.

std::vector<int> labust::vehicles::ThrustAllocator::dofs [protected]

Desired dofs.

Definition at line 265 of file ThrustAllocation.hpp.

std::vector<double> labust::vehicles::ThrustAllocator::group_scales [protected]

The scales per group.

Definition at line 273 of file ThrustAllocation.hpp.

std::vector< std::vector<int> > labust::vehicles::ThrustAllocator::groups [protected]

Thruster groups.

Definition at line 269 of file ThrustAllocation.hpp.

Definition at line 294 of file ThrustAllocation.hpp.

Eigen::VectorXd labust::vehicles::ThrustAllocator::tdes [protected]

The allocated thrusters.

Definition at line 286 of file ThrustAllocation.hpp.

The maximum and minimum thrust.

Definition at line 282 of file ThrustAllocation.hpp.

Definition at line 282 of file ThrustAllocation.hpp.

Allocation type, number of thrusters.

Definition at line 294 of file ThrustAllocation.hpp.


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


snippets
Author(s): Gyula Nagy
autogenerated on Mon Oct 6 2014 01:39:41