LDTravModelExtended.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the LABUST nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *
00034 *  Created on: Feb 25, 2013
00035 *  Author: Dula Nad
00036 *********************************************************************/
00037 #include <labust/navigation/LDTravModelExtended.hpp>
00038 
00039 #include <boost/numeric/ublas/banded.hpp>
00040 #include <boost/numeric/ublas/matrix_proxy.hpp>
00041 
00042 using namespace labust::navigation;
00043 
00044 LDTravModel::LDTravModel():
00045                 dvlModel(0),
00046                 xdot(0),
00047                 ydot(0)
00048 {
00049         this->initModel();
00050 };
00051 
00052 LDTravModel::~LDTravModel(){};
00053 
00054 void LDTravModel::initModel()
00055 {
00056   //std::cout<<"Init model."<<std::endl;
00057   x = vector::Zero(stateNum);
00058   xdot = 0;
00059   ydot = 0;
00060   //Setup the transition matrix
00061   derivativeAW();
00062   R0 = R;
00063   V0 = V;
00064 
00065   //std::cout<<"R:"<<R<<"\n"<<V<<std::endl;
00066 }
00067 
00068 void LDTravModel::calculateXYInovationVariance(const LDTravModel::matrix& P, double& xin,double &yin)
00069 {
00070         xin = sqrt(P(xp,xp)) + sqrt(R0(xp,xp));
00071         yin = sqrt(P(yp,yp)) + sqrt(R0(yp,yp));
00072 }
00073 
00074 void LDTravModel::calculateUVInovationVariance(const LDTravModel::matrix& P, double& uin,double &vin)
00075 {
00076         uin = sqrt(P(u,u)) + sqrt(R0(v,v));
00077         vin = sqrt(P(v,v)) + sqrt(R0(v,v));
00078 }
00079 
00080 void LDTravModel::step(const input_type& input)
00081 {
00082   x(u) += Ts*(-surge.Beta(x(u))/surge.alpha*x(u) + 1/surge.alpha * input(X));
00083   x(v) += Ts*(-sway.Beta(x(v))/sway.alpha*x(v) + 1/sway.alpha * input(Y));
00084   x(w) += Ts*(-heave.Beta(x(w))/heave.alpha*x(w) + 1/heave.alpha * (input(Z) + x(buoyancy)));
00085   x(p) += Ts*(-roll.Beta(x(p))/roll.alpha*x(p) + 1/roll.alpha * (input(Kroll) + x(roll_restore)));
00086   x(q) += Ts*(-pitch.Beta(x(p))/pitch.alpha*x(q) + 1/pitch.alpha * (input(M) + x(pitch_restore)));
00087   x(r) += Ts*(-yaw.Beta(x(r))/yaw.alpha*x(r) + 1/yaw.alpha * input(N) + 0*x(b));
00088 
00089   xdot = x(u)*cos(x(psi)) - x(v)*sin(x(psi)) + x(xc);
00090   ydot = x(u)*sin(x(psi)) + x(v)*cos(x(psi)) + x(yc);
00091   x(xp) += Ts * xdot;
00092   x(yp) += Ts * ydot;
00093   x(zp) += Ts * x(w);
00094   x(altitude) += -Ts * x(w);
00095   //\todo This is not actually true since angles depend on each other
00096   //\todo Also x,y are dependent on the whole rotation matrix.
00097   //\todo We make a simplification here for testing with small angles ~10°
00098   x(phi) += Ts * x(p);
00099   x(theta) += Ts * x(q);
00100   x(psi) += Ts * x(r);
00101 
00102   xk_1 = x;
00103 
00104   derivativeAW();
00105 };
00106 
00107 void LDTravModel::derivativeAW()
00108 {
00109         A = matrix::Identity(stateNum, stateNum);
00110 
00111         A(u,u) = 1-Ts*(surge.beta + 2*surge.betaa*fabs(x(u)))/surge.alpha;
00112         A(v,v) = 1-Ts*(sway.beta + 2*sway.betaa*fabs(x(v)))/sway.alpha;
00113         A(w,w) = 1-Ts*(heave.beta + 2*heave.betaa*fabs(x(w)))/heave.alpha;
00114         A(w,buoyancy) = Ts/heave.alpha;
00115         A(p,p) = 1-Ts*(roll.beta + 2*roll.betaa*fabs(x(p)))/roll.alpha;
00116         A(p,roll_restore) = Ts/roll.alpha;
00117         A(q,q) = 1-Ts*(pitch.beta + 2*pitch.betaa*fabs(x(q)))/pitch.alpha;
00118         A(q,pitch_restore) = Ts/pitch.alpha;
00119         A(r,r) = 1-Ts*(yaw.beta + 2*yaw.betaa*fabs(x(r)))/yaw.alpha;
00120         A(r,b) = 0*Ts;
00121 
00122         A(xp,u) = Ts*cos(x(psi));
00123         A(xp,v) = -Ts*sin(x(psi));
00124         A(xp,psi) = Ts*(-x(u)*sin(x(psi) - x(v)*cos(x(psi))));
00125         A(xp,xc) = Ts;
00126 
00127         A(yp,u) = Ts*sin(x(psi));
00128         A(yp,v) = Ts*cos(x(psi));
00129         A(yp,psi) = Ts*(x(u)*cos(x(psi)) - x(v)*sin(x(psi)));
00130         A(yp,yc) = Ts;
00131 
00132         A(zp,w) = Ts;
00133         //\todo If you don't want the altitude to contribute comment this out.
00134         A(altitude,w) = -Ts;
00135 
00136         A(phi,p) = Ts;
00137         A(theta,q) = Ts;
00138         A(psi,r) = Ts;
00139 }
00140 
00141 const LDTravModel::output_type& LDTravModel::update(vector& measurements, vector& newMeas)
00142 {
00143         std::vector<size_t> arrived;
00144         std::vector<double> dataVec;
00145 
00146         for (size_t i=0; i<newMeas.size(); ++i)
00147         {
00148                 if (newMeas(i))
00149                 {
00150                         arrived.push_back(i);
00151                         dataVec.push_back(measurements(i));
00152                         newMeas(i) = 0;
00153                 }
00154         }
00155 
00156         if (dvlModel != 0) derivativeH();
00157 
00158         measurement.resize(arrived.size());
00159         H = matrix::Zero(arrived.size(),stateNum);
00160         y = vector::Zero(arrived.size());
00161         R = matrix::Zero(arrived.size(),arrived.size());
00162         V = matrix::Zero(arrived.size(),arrived.size());
00163 
00164         for (size_t i=0; i<arrived.size();++i)
00165         {
00166                 measurement(i) = dataVec[i];
00167 
00168                 if (dvlModel != 0)
00169                 {
00170                         H.row(i)=Hnl.row(arrived[i]);
00171                         y(i) = ynl(arrived[i]);
00172                 }
00173                 else
00174                 {
00175                         H(i,arrived[i]) = 1;
00176                         y(i) = x(arrived[i]);
00177                 }
00178 
00179                 for (size_t j=0; j<arrived.size(); ++j)
00180                 {
00181                         R(i,j)=R0(arrived[i],arrived[j]);
00182                         V(i,j)=V0(arrived[i],arrived[j]);
00183                 }
00184         }
00185 
00186         //std::cout<<"Setup H:"<<H<<std::endl;
00187         //std::cout<<"Setup R:"<<R<<std::endl;
00188         //std::cout<<"Setup V:"<<V<<std::endl;
00189 
00190         return measurement;
00191 }
00192 
00193 void LDTravModel::estimate_y(output_type& y)
00194 {
00195   y=this->y;
00196 }
00197 
00198 void LDTravModel::derivativeH()
00199 {
00200         Hnl=matrix::Identity(stateNum,stateNum);
00201         ynl = Hnl*x;
00202 
00203         switch (dvlModel)
00204         {
00205         case 1:
00206                 //Correct the nonlinear part
00207                 ynl(u) = x(u)+x(xc)*cos(x(psi))+x(yc)*sin(x(psi));
00208                 ynl(v) = x(v)-x(xc)*sin(x(psi))+x(yc)*cos(x(psi));
00209 
00210                 //Correct for the nonlinear parts
00211                 Hnl(u,u) = 1;
00212                 Hnl(u,xc) = cos(x(psi));
00213                 Hnl(u,yc) = sin(x(psi));
00214                 Hnl(u,psi) = -x(xc)*sin(x(psi)) + x(yc)*cos(x(psi));
00215 
00216                 Hnl(v,v) = 1;
00217                 Hnl(v,xc) = -sin(x(psi));
00218                 Hnl(v,yc) = cos(x(psi));
00219                 Hnl(v,psi) = -x(xc)*cos(x(psi)) - x(yc)*sin(x(psi));
00220                 break;
00221         case 2:
00222                 //Correct the nonlinear part
00223           y(u) = x(u)*cos(x(psi)) - x(v)*sin(x(psi)) + x(xc);
00224           y(v) = x(u)*sin(x(psi)) + x(v)*cos(x(psi)) + x(yc);
00225 
00226           //Correct for the nonlinear parts
00227                 Hnl(u,xc) = 1;
00228                 Hnl(u,u) = cos(x(psi));
00229                 Hnl(u,v) = -sin(x(psi));
00230                 Hnl(u,psi) = -x(u)*sin(x(psi)) - x(v)*cos(x(psi));
00231 
00232                 Hnl(v,yc) = 1;
00233                 Hnl(v,u) = sin(x(psi));
00234                 Hnl(v,v) = cos(x(psi));
00235                 Hnl(v,psi) = x(u)*cos(x(psi)) - x(v)*sin(x(psi));
00236                 break;
00237         }
00238 }
00239 


ldtravocean
Author(s):
autogenerated on Fri Feb 7 2014 11:37:01