#include <x2d_adaptive.h>
Public Member Functions | |
const std::vector< double > & | allocate (const Eigen::VectorXd &tau) |
bool | configure (ros::NodeHandle &nh, ros::NodeHandle &ph) |
const Eigen::VectorXd & | tauA () const |
const std::vector< bool > & | windup () |
X2dAdaptive () | |
Main constructor. | |
Private Member Functions | |
void | recalcOpLimits (Eigen::Vector4d &used, Eigen::Vector4d &pmax, Eigen::Vector4d &pmin, Eigen::Vector4d *cmax, Eigen::Vector4d *cmin) |
Helper method for re-calculation of operational limits. | |
bool | saturate (Eigen::Vector4d &t, const Eigen::Vector4d &pmin, const Eigen::Vector4d &pmax) |
Helper function for coercing XY in-place. | |
bool | saturateN (Eigen::Vector4d &t, const Eigen::Vector4d &pmin, const Eigen::Vector4d &pmax) |
Helper function for coercing N in-place. | |
bool | secondRun (const Eigen::VectorXd &tau, const Eigen::VectorXd &tmax, const Eigen::VectorXd &tmin, Eigen::VectorXd *tauA, Eigen::VectorXd *tT) |
Helper function to calculate the daisy chain. | |
Private Attributes | |
std::vector< bool > | _windup |
The windup flags. | |
bool | daisy_chain |
Flag to control if the daisy chain step should be applied. | |
double | minN |
Minimum guaranteed yaw torque. | |
bool | multi_chain |
Flag to control multi-level daisy chain. | |
Eigen::VectorXd | tau_ach |
The final achieved tau. | |
ThrusterConfiguration | thrusters |
The thruster configuration. | |
Eigen::Vector4d | tnmax |
Maximum thrust reserved for torque. | |
Eigen::Vector4d | tnmin |
Minimum thrust reserved for torque. |
The class implements a adaptive scheme thruster allocation that ensures a minimal achievable yaw torque and allows for thruster scaling.
The thruster number is assumed to be 4; distributed in an X-configuration. The number of DoF is assumed to be 3; X,Y,N. No assumption is made on thruster symmetry.
Definition at line 60 of file x2d_adaptive.h.
Main constructor.
Definition at line 49 of file x2d_adaptive.cpp.
const std::vector< double > & X2dAdaptive::allocate | ( | const Eigen::VectorXd & | tau | ) | [virtual] |
The main allocation function that distributes desired forces and moments directly to the thrusters.
Implements labust::allocation::AllocationInterface.
Definition at line 72 of file x2d_adaptive.cpp.
bool X2dAdaptive::configure | ( | ros::NodeHandle & | nh, |
ros::NodeHandle & | ph | ||
) | [virtual] |
The main configuration method. The method load parameters and initializes the subscribers and publishers of the allocation.
Implements labust::allocation::AllocationInterface.
Definition at line 56 of file x2d_adaptive.cpp.
void X2dAdaptive::recalcOpLimits | ( | Eigen::Vector4d & | used, |
Eigen::Vector4d & | pmax, | ||
Eigen::Vector4d & | pmin, | ||
Eigen::Vector4d * | cmax, | ||
Eigen::Vector4d * | cmin | ||
) | [private] |
Helper method for re-calculation of operational limits.
Definition at line 151 of file x2d_adaptive.cpp.
bool X2dAdaptive::saturate | ( | Eigen::Vector4d & | t, |
const Eigen::Vector4d & | pmin, | ||
const Eigen::Vector4d & | pmax | ||
) | [private] |
Helper function for coercing XY in-place.
Definition at line 184 of file x2d_adaptive.cpp.
bool X2dAdaptive::saturateN | ( | Eigen::Vector4d & | t, |
const Eigen::Vector4d & | pmin, | ||
const Eigen::Vector4d & | pmax | ||
) | [private] |
Helper function for coercing N in-place.
Definition at line 171 of file x2d_adaptive.cpp.
bool X2dAdaptive::secondRun | ( | const Eigen::VectorXd & | tau, |
const Eigen::VectorXd & | tmax, | ||
const Eigen::VectorXd & | tmin, | ||
Eigen::VectorXd * | tauA, | ||
Eigen::VectorXd * | tT | ||
) | [private] |
Helper function to calculate the daisy chain.
Definition at line 202 of file x2d_adaptive.cpp.
const Eigen::VectorXd& labust::allocation::X2dAdaptive::tauA | ( | ) | const [inline, virtual] |
The method returns the last achieved tau vector.
Implements labust::allocation::AllocationInterface.
Definition at line 83 of file x2d_adaptive.h.
const std::vector<bool>& labust::allocation::X2dAdaptive::windup | ( | ) | [inline, virtual] |
The method returns the windup flags per degree of freedom.
Implements labust::allocation::AllocationInterface.
Definition at line 88 of file x2d_adaptive.h.
std::vector<bool> labust::allocation::X2dAdaptive::_windup [private] |
The windup flags.
Definition at line 111 of file x2d_adaptive.h.
bool labust::allocation::X2dAdaptive::daisy_chain [private] |
Flag to control if the daisy chain step should be applied.
Definition at line 116 of file x2d_adaptive.h.
double labust::allocation::X2dAdaptive::minN [private] |
Minimum guaranteed yaw torque.
Definition at line 114 of file x2d_adaptive.h.
bool labust::allocation::X2dAdaptive::multi_chain [private] |
Flag to control multi-level daisy chain.
Definition at line 118 of file x2d_adaptive.h.
Eigen::VectorXd labust::allocation::X2dAdaptive::tau_ach [private] |
The final achieved tau.
Definition at line 124 of file x2d_adaptive.h.
The thruster configuration.
Definition at line 108 of file x2d_adaptive.h.
Eigen::Vector4d labust::allocation::X2dAdaptive::tnmax [private] |
Maximum thrust reserved for torque.
Definition at line 120 of file x2d_adaptive.h.
Eigen::Vector4d labust::allocation::X2dAdaptive::tnmin [private] |
Minimum thrust reserved for torque.
Definition at line 122 of file x2d_adaptive.h.