Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 #ifndef ALLOCATION_X2D_ADAPTIVE_H
00035 #define ALLOCATION_X2D_ADAPTIVE_H
00036 #include <labust/allocation/allocation_interface.h>
00037 #include <labust/allocation/thruster_configuration.h>
00038 
00039 #include <std_msgs/Float32.h>
00040 #include <ros/ros.h>
00041 
00042 #include <boost/array.hpp>
00043 #include <Eigen/Dense>
00044 
00045 #include <cmath>
00046 #include <vector>
00047 
00048 namespace labust
00049 {
00050         namespace allocation
00051         {
00060                 class X2dAdaptive : public virtual AllocationInterface
00061                 {
00062                 public:
00064                         X2dAdaptive();
00065 
00070                         bool configure(ros::NodeHandle& nh, ros::NodeHandle& ph);
00071 
00078                         const std::vector<double>& allocate(const Eigen::VectorXd& tau);
00079 
00083                         const Eigen::VectorXd& tauA() const {return tau_ach;};
00084 
00088                         const std::vector<bool>& windup(){return _windup;};
00089 
00090                 private:
00092                         void recalcOpLimits(Eigen::Vector4d& used, Eigen::Vector4d& pmax,
00093                                         Eigen::Vector4d& pmin, Eigen::Vector4d* cmax,
00094                                         Eigen::Vector4d* cmin);
00095 
00097                         bool saturate(Eigen::Vector4d& t, const Eigen::Vector4d& pmin, const Eigen::Vector4d& pmax);
00099                         bool saturateN(Eigen::Vector4d& t, const Eigen::Vector4d& pmin, const Eigen::Vector4d& pmax);
00100 
00102                         bool secondRun(const Eigen::VectorXd& tau, const Eigen::VectorXd& tmax,
00103                                         const Eigen::VectorXd& tmin, Eigen::VectorXd* tauA,
00104                                         Eigen::VectorXd* tT);
00105 
00106 
00108                         ThrusterConfiguration thrusters;
00109 
00111                         std::vector<bool> _windup;
00112 
00114                         double minN;
00116                         bool daisy_chain;
00118                         bool multi_chain;
00120                         Eigen::Vector4d tnmax;
00122                         Eigen::Vector4d tnmin;
00124                         Eigen::VectorXd tau_ach;
00125                 };
00126         }
00127 }
00128 
00129 
00130 #endif