$search
00001 //================================================================================================= 00002 // Copyright (c) 2011, Johannes Meyer, 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/measurements/heading.h> 00030 00031 namespace hector_pose_estimation { 00032 00033 HeadingModel::HeadingModel() 00034 : MeasurementModel(MeasurementDimension) 00035 { 00036 parameters().add("stddev", stddev_, 10.0*M_PI/180.0); 00037 } 00038 00039 bool HeadingModel::init() 00040 { 00041 NoiseCovariance noise = 0.0; 00042 noise(1,1) = pow(stddev_, 2); 00043 this->AdditiveNoiseSigmaSet(noise); 00044 return true; 00045 } 00046 00047 HeadingModel::~HeadingModel() {} 00048 00049 bool HeadingModel::applyStatusMask(const SystemStatus &status) const { 00050 if (status & STATE_YAW) return false; 00051 return true; 00052 } 00053 00054 SystemStatus HeadingModel::getStatusFlags() const { 00055 return STATE_YAW; 00056 } 00057 00058 ColumnVector HeadingModel::ExpectedValueGet() const { 00059 const double qw = x_(QUATERNION_W); 00060 const double qx = x_(QUATERNION_X); 00061 const double qy = x_(QUATERNION_Y); 00062 const double qz = x_(QUATERNION_Z); 00063 00064 y_(1) = atan2(2*(qx*qy + qw*qz), qw*qw + qx*qx - qy*qy - qz*qz); 00065 00066 return y_; 00067 } 00068 00069 Matrix HeadingModel::dfGet(unsigned int i) const { 00070 if (i != 0) return Matrix(); 00071 00072 const double qw = x_(QUATERNION_W); 00073 const double qx = x_(QUATERNION_X); 00074 const double qy = x_(QUATERNION_Y); 00075 const double qz = x_(QUATERNION_Z); 00076 const double t1 = qw*qw + qx*qx - qy*qy - qz*qz; 00077 const double t2 = 2*(qx*qy + qw*qz); 00078 const double t3 = 1.0 / (t1*t1 + t2*t2); 00079 00080 C_(1,QUATERNION_W) = 2.0 * t3 * (qz * t1 - qw * t2); 00081 C_(1,QUATERNION_X) = 2.0 * t3 * (qy * t1 - qx * t2); 00082 C_(1,QUATERNION_Y) = 2.0 * t3 * (qx * t1 + qy * t2); 00083 C_(1,QUATERNION_Z) = 2.0 * t3 * (qw * t1 + qz * t2); 00084 00085 return C_; 00086 } 00087 00088 } // namespace hector_pose_estimation