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 
00035 
00036 
00037 #include <labust/navigation/XYModel.hpp>
00038 #include <vector>
00039 
00040 using namespace labust::navigation;
00041 
00042 XYModel::XYModel():
00043                 xdot(0),
00044                 ydot(0)
00045 {
00046         this->initModel();
00047 };
00048 
00049 XYModel::~XYModel(){};
00050 
00051 void XYModel::initModel()
00052 {
00053   
00054   x = vector::Zero(stateNum);
00055   xdot = 0;
00056   ydot = 0;
00057   
00058   derivativeAW();
00059   
00060 }
00061 
00062 const XYModel::output_type& XYModel::update(vector& measurements, vector& newMeas)
00063 {
00064         std::vector<size_t> arrived;
00065         std::vector<double> dataVec;
00066 
00067         for (size_t i=0; i<newMeas.size(); ++i)
00068         {
00069                 if (newMeas(i))
00070                 {
00071                         arrived.push_back(i);
00072                         dataVec.push_back(measurements(i));
00073                         newMeas(i) = 0;
00074                 }
00075         }
00076 
00077         measurement.resize(arrived.size());
00078         H = matrix::Zero(arrived.size(),stateNum);
00079         R = matrix::Zero(arrived.size(),arrived.size());
00080         V = matrix::Zero(arrived.size(),arrived.size());
00081 
00082         for (size_t i=0; i<arrived.size();++i)
00083         {
00084                 measurement(i) = dataVec[i];
00085                 H(i,arrived[i]) = 1;
00086                 for (size_t j=0; j<arrived.size(); ++j)
00087                 {
00088                         R(i,j)=R0(arrived[i],arrived[j]);
00089                         V(i,j)=V0(arrived[i],arrived[j]);
00090                 }
00091         }
00092 
00093         
00094         
00095         
00096 
00097         return measurement;
00098 }
00099 
00100 
00101 
00102 
00103 
00104 
00105 
00106 
00107 
00108 
00109 
00110 
00111 
00112 
00113 
00114 
00115 
00116 
00117 
00118 
00119 
00120 
00121 
00122 
00123 
00124 
00125 
00126 
00127 
00128 
00129 void XYModel::calculateXYInovationVariance(const XYModel::matrix& P, double& xin,double &yin)
00130 {
00131         xin = sqrt(P(xp,xp)) + sqrt(R0(xp,xp));
00132         yin = sqrt(P(yp,yp)) + sqrt(R0(yp,yp));
00133 }
00134 
00135 void XYModel::step(const input_type& input)
00136 {
00137   x(u) += Ts*(-surge.Beta(x(u))/surge.alpha*x(u) + 1/surge.alpha * input(X));
00138   x(v) += Ts*(-sway.Beta(x(v))/sway.alpha*x(v) + 1/sway.alpha * input(Y));
00139   x(r) += Ts*(-yaw.Beta(x(r))/yaw.alpha*x(r) + 1/yaw.alpha * input(N) + 0*x(b2));
00140 
00141   xdot = x(u)*cos(x(psi)) - x(v)*sin(x(psi)) + x(xc);
00142   ydot = x(u)*sin(x(psi)) + x(v)*cos(x(psi)) + x(yc);
00143   x(xp) += Ts * xdot;
00144   x(yp) += Ts * ydot;
00145   x(psi) += Ts * (x(r) + 0*x(b1));
00146 
00147   xk_1 = x;
00148 
00149   derivativeAW();
00150 };
00151 
00152 void XYModel::derivativeAW()
00153 {
00154         A = matrix::Identity(stateNum, stateNum);
00155 
00156         A(u,u) = 1-Ts*(surge.beta + 2*surge.betaa*fabs(x(u)))/surge.alpha;
00157         A(v,v) = 1-Ts*(sway.beta + 2*sway.betaa*fabs(x(v)))/sway.alpha;
00158         A(r,r) = 1-Ts*(yaw.beta + 2*yaw.betaa*fabs(x(r)))/yaw.alpha;
00159         A(r,b2) = 0*Ts;
00160 
00161         A(xp,u) = Ts*cos(x(psi));
00162         A(xp,v) = -Ts*sin(x(psi));
00163         A(xp,psi) = Ts*(-x(u)*sin(x(psi)) - x(v)*cos(x(psi)));
00164         A(xp,xc) = Ts;
00165 
00166         A(yp,u) = Ts*sin(x(psi));
00167         A(yp,v) = Ts*cos(x(psi));
00168         A(yp,psi) = Ts*(x(u)*cos(x(psi)) - x(v)*sin(x(psi)));
00169         A(yp,yc) = Ts;
00170 
00171         A(psi,r) = Ts;
00172         A(psi,b1) = 0*Ts;
00173 }
00174 
00175 
00176 
00177 
00178 
00179 
00180 
00181 
00182 
00183 
00184 
00185 
00186 
00187 
00188 
00189 
00190 
00191 
00192 
00193 
00194 
00195 
00196 
00197 
00198 
00199 
00200 
00201 
00202 void XYModel::estimate_y(output_type& y)
00203 {
00204   y=H*x;
00205 }
00206