$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 #ifndef HECTOR_POSE_ESTIMATION_SYSTEM_H 00030 #define HECTOR_POSE_ESTIMATION_SYSTEM_H 00031 00032 #include "system_model.h" 00033 #include "system_input.h" 00034 00035 namespace BFL { class KalmanFilter; } 00036 00037 namespace hector_pose_estimation { 00038 00039 class PoseEstimation; 00040 00041 class System 00042 { 00043 public: 00044 System(const std::string& name); 00045 virtual ~System(); 00046 00047 template <typename ConcreteModel> static boost::shared_ptr<System> create(ConcreteModel *model, const std::string& name = "system"); 00048 00049 virtual const std::string& getName() const { return name_; } 00050 virtual void setName(const std::string& name) { name_ = name; } 00051 00052 virtual SystemModel *getModel() const = 0; 00053 00054 virtual bool init(); 00055 virtual void cleanup(); 00056 virtual void reset(); 00057 00058 virtual SystemStatus getStatusFlags() const { return status_flags_; } 00059 00060 virtual ParameterList& parameters() { return parameters_; } 00061 virtual const ParameterList& parameters() const { return parameters_; } 00062 00063 BFL::Gaussian *getPrior(); 00064 virtual const SystemInput& getInput() const = 0; 00065 virtual void setInput(const SystemInput& input) = 0; 00066 00067 virtual bool update(PoseEstimation &estimator, double dt) = 0; 00068 virtual void updated(); 00069 virtual StateVector limitState(StateVector state) const; 00070 00071 protected: 00072 void updateInternal(PoseEstimation &estimator, double dt, ColumnVector const& u); 00073 00074 protected: 00075 std::string name_; 00076 ParameterList parameters_; 00077 SystemStatus status_flags_; 00078 BFL::Gaussian prior_; 00079 }; 00080 00081 typedef boost::shared_ptr<System> SystemPtr; 00082 00083 template <typename ConcreteModel, typename ConcreteInput = typename Input_<ConcreteModel>::Type > 00084 class System_ : public System 00085 { 00086 public: 00087 typedef ConcreteModel Model; 00088 typedef ConcreteInput Input; 00089 static const unsigned int InputDimension = Model::InputDimension; 00090 typedef typename Model::InputVector InputVector; 00091 00092 System_(const std::string& name = "system") 00093 : System(name) 00094 , model_(new Model) 00095 { 00096 parameters_.add(model_->parameters()); 00097 } 00098 00099 System_(Model *model, const std::string& name) 00100 : System(name) 00101 , model_(model) 00102 { 00103 parameters_.add(model_->parameters()); 00104 } 00105 virtual SystemModel *getModel() const { return model_.get(); } 00106 00107 virtual const Input& getInput() const { return input_; } 00108 virtual void setInput(const Input& input) { input_ = input; } 00109 virtual void setInput(const SystemInput& input) { 00110 try { 00111 input_ = dynamic_cast<const Input&>(input); 00112 } catch(std::bad_cast& e) { 00113 std::cerr << "In system " << getName() << ": " << e.what() << std::endl; 00114 std::cerr << "Expected type " << std::string(typeid(Input).name()) << ", you gave me " << std::string(typeid(input).name()) << std::endl; 00115 } 00116 } 00117 00118 virtual bool update(PoseEstimation &estimator, double dt); 00119 00120 private: 00121 boost::shared_ptr<Model> model_; 00122 Input input_; 00123 }; 00124 00125 template <class ConcreteModel, class ConcreteInput> 00126 bool System_<ConcreteModel, ConcreteInput>::update(PoseEstimation &estimator, double dt) 00127 { 00128 updateInternal(estimator, dt, input_.getVector()); 00129 return true; 00130 } 00131 00132 template <typename ConcreteModel> 00133 SystemPtr System::create(ConcreteModel *model, const std::string& name) 00134 { 00135 return SystemPtr(new System_<ConcreteModel>(model, name)); 00136 } 00137 00138 } // namespace hector_pose_estimation 00139 00140 #endif // HECTOR_POSE_ESTIMATION_SYSTEM_H