$search
00001 //================================================================================================= 00002 // Copyright (c) 2011, Johannes Meyer and Martin Nowara, TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Flight Systems and Automatic Control group, 00013 // TU Darmstadt, nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #include <hector_pose_estimation/system_model.h> 00030 00031 namespace hector_pose_estimation { 00032 00033 SystemModel::SystemModel() 00034 : BFL::AnalyticConditionalGaussianAdditiveNoise(StateDimension, 2) 00035 , BFL::AnalyticSystemModelGaussianUncertainty(this) 00036 , dt_(0.0) 00037 , x_(static_cast<const StateVector&>(ConditionalArgumentGet(0))) 00038 , u_(static_cast<const ColumnVector&>(ConditionalArgumentGet(1))) 00039 , x_pred_(StateDimension) 00040 , A_(StateDimension,StateDimension) 00041 , measurement_status_(0) 00042 { 00043 A_ = 0.0; 00044 for(unsigned int i = 1; i <= StateDimension; i++) A_(i,i) = 1.0; 00045 AdditiveNoiseMuSet(StateVector(0.0)); 00046 AdditiveNoiseSigmaSet(SymmetricMatrix_<StateDimension>(0.0)); 00047 } 00048 00049 SystemModel::~SystemModel() 00050 { 00051 } 00052 00053 void SystemModel::getPrior(BFL::Gaussian &prior) const { 00054 StateVector mu = 0; 00055 mu(QUATERNION_W) = 1.0; 00056 StateCovariance cov = 0; 00057 cov(QUATERNION_W,QUATERNION_W) = 0.25 * 1.0; 00058 cov(QUATERNION_X,QUATERNION_X) = 0.25 * 1.0; 00059 cov(QUATERNION_Y,QUATERNION_Y) = 0.25 * 1.0; 00060 cov(QUATERNION_Z,QUATERNION_Z) = 0.25 * 1.0; 00061 #ifdef USE_RATE_SYSTEM_MODEL 00062 cov(RATE_X,RATE_X) = pow(0.0 * M_PI/180.0, 2); 00063 cov(RATE_Y,RATE_Y) = pow(0.0 * M_PI/180.0, 2); 00064 cov(RATE_Z,RATE_Z) = pow(0.0 * M_PI/180.0, 2); 00065 #endif // USE_RATE_SYSTEM_MODEL 00066 cov(POSITION_X,POSITION_X) = 0.0; 00067 cov(POSITION_Y,POSITION_Y) = 0.0; 00068 cov(POSITION_Z,POSITION_Z) = 0.0; 00069 cov(VELOCITY_X,VELOCITY_X) = 0.0; 00070 cov(VELOCITY_Y,VELOCITY_Y) = 0.0; 00071 cov(VELOCITY_Z,VELOCITY_Z) = 0.0; 00072 cov(BIAS_ACCEL_X,BIAS_ACCEL_X) = 0.0; 00073 cov(BIAS_ACCEL_Y,BIAS_ACCEL_Y) = 0.0; 00074 cov(BIAS_ACCEL_Z,BIAS_ACCEL_Z) = 0.0; 00075 cov(BIAS_GYRO_X,BIAS_GYRO_X) = pow(5.0 * M_PI/180.0, 2); 00076 cov(BIAS_GYRO_Y,BIAS_GYRO_Y) = pow(5.0 * M_PI/180.0, 2); 00077 cov(BIAS_GYRO_Z,BIAS_GYRO_Z) = pow(5.0 * M_PI/180.0, 2); 00078 00079 prior.ExpectedValueSet(mu); 00080 prior.CovarianceSet(cov); 00081 } 00082 00083 SymmetricMatrix SystemModel::CovarianceGet(double dt) const 00084 { 00085 // return this->AdditiveNoiseSigmaGet() * (dt*dt); 00086 return this->AdditiveNoiseSigmaGet() * dt; 00087 } 00088 00089 } // namespace hector_pose_estimation