imu_model.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2013, 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 #ifndef HECTOR_POSE_ESTIMATION_IMU_MODEL_H
00030 #define HECTOR_POSE_ESTIMATION_IMU_MODEL_H
00031 
00032 #include <hector_pose_estimation/system_model.h>
00033 #include <hector_pose_estimation/system.h>
00034 
00035 namespace hector_pose_estimation {
00036 
00037 class GyroModel : public TimeContinuousSystemModel_<GyroModel, 3>
00038 {
00039 public:
00040   enum StateIndex {
00041     BIAS_GYRO_X = 0,
00042     BIAS_GYRO_Y,
00043     BIAS_GYRO_Z
00044   };
00045 
00046   GyroModel();
00047   virtual ~GyroModel();
00048 
00049   SubState& sub(State& state) const { return *drift_; }
00050   const SubState& sub(const State& state) const { return *drift_; }
00051 
00052   virtual bool init(PoseEstimation& estimator, State& state);
00053 
00054   using TimeContinuousSystemModel_<GyroModel, 3>::getSystemNoise;
00055   virtual void getSystemNoise(NoiseVariance& Q, const State& state, bool init);
00056   using TimeContinuousSystemModel_<GyroModel, 3>::getStateJacobian;
00057   virtual void getStateJacobian(SystemMatrix& A1, CrossSystemMatrix& A01, const State& state, bool init);
00058 
00059   ConstStateVectorSegment getBias() const { return drift_->getVector(); }
00060 
00061 private:
00062   SubStatePtr drift_;
00063   double rate_stddev_;
00064   double rate_drift_;
00065 };
00066 
00067 class AccelerometerModel : public TimeContinuousSystemModel_<AccelerometerModel, 3>
00068 {
00069 public:
00070   enum StateIndex {
00071     BIAS_ACCEL_X = 0,
00072     BIAS_ACCEL_Y,
00073     BIAS_ACCEL_Z
00074   };
00075 
00076   AccelerometerModel();
00077   virtual ~AccelerometerModel();
00078 
00079   SubState& sub(State& state) const { return *drift_; }
00080   const SubState& sub(const State& state) const { return *drift_; }
00081 
00082   virtual bool init(PoseEstimation& estimator, State& state);
00083 
00084   using TimeContinuousSystemModel_<AccelerometerModel, 3>::getSystemNoise;
00085   virtual void getSystemNoise(NoiseVariance& Q, const State& state, bool init);
00086   using TimeContinuousSystemModel_<AccelerometerModel, 3>::getStateJacobian;
00087   virtual void getStateJacobian(SystemMatrix& A1, CrossSystemMatrix& A01, const State& state, bool init);
00088 
00089   ConstStateVectorSegment getBias() const { return drift_->getVector(); }
00090 
00091 private:
00092   SubStatePtr drift_;
00093   double acceleration_stddev_;
00094   double acceleration_drift_;
00095 };
00096 
00097 typedef System_<GyroModel> Gyro;
00098 extern template class System_<GyroModel>;
00099 
00100 typedef System_<AccelerometerModel> Accelerometer;
00101 extern template class System_<AccelerometerModel>;
00102 
00103 }
00104 
00105 #endif // HECTOR_POSE_ESTIMATION_IMU_MODEL_H


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 00:24:16