kinematic_model.h
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 *  Author: Dula Nad
00035 *  Created: 01.02.2010.
00036 *********************************************************************/
00037 #ifndef LABUST_SIM_KINEMATICMODEL_H
00038 #define LABUST_SIM_KINEMATICMODEL_H
00039 #include <labust/simulation/matrixfwd.hpp>
00040 #include <labust/tools/conversions.hpp>
00041 
00042 namespace labust
00043 {
00044   namespace simulation
00045   {
00051     class KinematicModel
00052     {
00053     public:
00054       enum {x=0,y,z};
00055       enum {phi=0,theta,psi};
00056       enum {u=0,v,w,p,q,r};
00058       KinematicModel();
00065       void step(const vector& nu);
00072       inline const vector3& position() const {return this->pos;};
00079       inline const vector3& orientation()
00080       {
00081           labust::tools::eulerZYXFromQuaternion(this->quat, this->rpy);
00082           return rpy;
00083       };
00090       inline void setPosition(const vector3& pos, const vector3& rpy)
00091       {
00092         this->pos = this->pos0 = pos;
00093         labust::tools::quaternionFromEulerZYX(rpy(phi),rpy(theta),rpy(psi), this->quat);
00094       }
00101       inline void setPosition(const vector3& pos, const quaternion& quat)
00102       {
00103         this->pos = this->pos0 = pos;
00104         this->quat = this->quat0 = quat;
00105       }
00111       inline void init(double depth = 0)
00112       {
00113         this->reset();
00114         //Calculate and set the the neutral depth where W=B
00115         pos(z) = depth;
00116       }
00120       void reset()
00121       {
00122         this->pos = this->pos0;
00123         this->quat = this->quat0;
00124       };
00126       inline void setTs(double Ts){this->dT = Ts;};
00127 
00128     protected:
00130       double dT;
00132       vector3 current;
00134       vector3 pos0;
00136       vector3 pos;
00138       quaternion quat0;
00140       quaternion quat;
00142       vector3 rpy;
00143     };
00144   }
00145 }
00146 
00147 /* LABUST_SIM_KINEMATICMODEL_H */
00148 #endif


labust_sim
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:38