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 #include <hector_pose_estimation/system/imu_input.h>
00036 
00037 namespace hector_pose_estimation {
00038 
00039 class GyroModel : public TimeContinuousSystemModel_<GyroModel,3>
00040 {
00041 public:
00042   using TimeContinuousSystemModel_<GyroModel,3>::SubState;
00043 
00044   GyroModel();
00045   virtual ~GyroModel();
00046 
00047   bool init(PoseEstimation& estimator, System &system, State& state);
00048   void getPrior(State &state);
00049 
00050   ColumnVector3 getError() const { return bias_->getVector(); }
00051 
00052   ColumnVector3 getRate(const ImuInput::RateType& imu_rate, const State& state) const;
00053   void getRateJacobian(SystemMatrixBlock& C, const State& state, bool init = true);
00054   void getRateNoise(CovarianceBlock Q, const State& state, bool init = true);
00055 
00056   using TimeContinuousSystemModel_<GyroModel,3>::getSystemNoise;
00057   void getSystemNoise(NoiseVariance& Q, const State& state, bool init = true);
00058 
00059 private:
00060   typename SubState::Ptr bias_;
00061   double rate_stddev_;
00062   double rate_drift_;
00063 };
00064 
00065 class AccelerometerModel : public TimeContinuousSystemModel_<AccelerometerModel,3>
00066 {
00067 public:
00068   using TimeContinuousSystemModel_<AccelerometerModel,3>::SubState;
00069 
00070   AccelerometerModel();
00071   virtual ~AccelerometerModel();
00072 
00073   bool init(PoseEstimation& estimator, System &system, State& state);
00074   void getPrior(State &state);
00075 
00076   ColumnVector3 getError() const { return bias_->getVector(); }
00077 
00078   ColumnVector3 getAcceleration(const ImuInput::AccelerationType& imu_acceleration, const State& state) const;
00079   void getAccelerationJacobian(SystemMatrixBlock& C, const State& state, bool init = true);
00080   void getAccelerationNoise(CovarianceBlock Q, const State& state, bool init = true);
00081 
00082   using TimeContinuousSystemModel_<AccelerometerModel,3>::getSystemNoise;
00083   void getSystemNoise(NoiseVariance& Q, const State& state, bool init = true);
00084 
00085 private:
00086   typename SubState::Ptr bias_;
00087   double acceleration_stddev_;
00088   double acceleration_drift_;
00089 };
00090 
00091 typedef System_<GyroModel> Gyro;
00092 extern template class System_<GyroModel>;
00093 
00094 typedef System_<AccelerometerModel> Accelerometer;
00095 extern template class System_<AccelerometerModel>;
00096 
00097 }
00098 
00099 #endif // HECTOR_POSE_ESTIMATION_IMU_MODEL_H


hector_pose_estimation_core
Author(s): Johannes Meyer
autogenerated on Mon Aug 22 2016 03:53:11