$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 #ifndef HECTOR_POSE_ESTIMATION_SYSTEM_MODEL_H 00030 #define HECTOR_POSE_ESTIMATION_SYSTEM_MODEL_H 00031 00032 #include <hector_pose_estimation/types.h> 00033 #include <hector_pose_estimation/parameters.h> 00034 00035 #include <bfl/model/analyticsystemmodel_gaussianuncertainty.h> 00036 #include <bfl/pdf/analyticconditionalgaussian_additivenoise.h> 00037 #include <bfl/pdf/gaussian.h> 00038 00039 #include <string> 00040 00041 namespace hector_pose_estimation { 00042 00043 class PoseEstimation; 00044 00045 class SystemModel : public BFL::AnalyticConditionalGaussianAdditiveNoise, public BFL::AnalyticSystemModelGaussianUncertainty { 00046 public: 00047 SystemModel(); 00048 virtual ~SystemModel(); 00049 00050 virtual std::string getName() const { return std::string(); } 00051 00052 virtual bool init() { return true; } 00053 virtual void cleanup() { } 00054 virtual void reset() { } 00055 00056 ParameterList& parameters() { return parameters_; } 00057 const ParameterList& parameters() const { return parameters_; } 00058 00059 void set_dt(double dt) { dt_ = dt; } 00060 double get_dt() const { return dt_; } 00061 00062 virtual void setMeasurementStatus(const SystemStatus& status) { measurement_status_ = status; } 00063 virtual SystemStatus getStatusFlags() const { return measurement_status_; } 00064 00065 virtual void getPrior(BFL::Gaussian &prior) const; 00066 00067 virtual SymmetricMatrix CovarianceGet(double dt) const; 00068 virtual SymmetricMatrix CovarianceGet() const { 00069 return CovarianceGet(dt_); 00070 } 00071 00072 virtual ColumnVector ExpectedValueGet(double dt) const { 00073 return ExpectedValueGet(); 00074 } 00075 virtual ColumnVector ExpectedValueGet() const { 00076 return ExpectedValueGet(dt_); 00077 } 00078 00079 virtual Matrix dfGet(unsigned int i, double dt) const { 00080 return dfGet(i); 00081 } 00082 virtual Matrix dfGet(unsigned int i) const { 00083 return dfGet(i, dt_); 00084 } 00085 00086 virtual void Limit(StateVector& x) const { 00087 } 00088 00089 virtual double getGravity() const { return 0.0; } 00090 00091 protected: 00092 double dt_; 00093 ParameterList parameters_; 00094 00095 protected: 00096 const StateVector& x_; 00097 const ColumnVector& u_; 00098 mutable StateVector x_pred_; 00099 mutable Matrix A_; 00100 SystemStatus measurement_status_; 00101 }; 00102 00103 } // namespace hector_pose_estimation 00104 00105 #endif // HECTOR_POSE_ESTIMATION_SYSTEM_MODEL_H