sensor_model.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, 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_GAZEBO_PLUGINS_SENSOR_MODEL_H
00030 #define HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H
00031 
00032 #include <sdf/sdf.hh>
00033 #include <gazebo/math/Vector3.hh>
00034 
00035 namespace gazebo {
00036 
00037 template <typename T>
00038 class SensorModel_ {
00039 public:
00040   SensorModel_();
00041   virtual ~SensorModel_();
00042 
00043   virtual void Load(sdf::ElementPtr _sdf, const std::string& prefix = std::string());
00044 
00045   virtual T operator()(const T& value) const { return value + current_error_; }
00046   virtual T operator()(const T& value, double dt) { return value + update(dt); }
00047 
00048   virtual T update(double dt);
00049   virtual void reset(const T& value = T());
00050 
00051   virtual const T& getCurrentError() const { return current_error_; }
00052   virtual const T& getCurrentDrift() const { return current_drift_; }
00053 
00054   virtual void setCurrentDrift(const T& new_drift) { current_drift_ = new_drift; }
00055 
00056 private:
00057   virtual bool LoadImpl(sdf::ElementPtr _element, T& _value);
00058 
00059 public:
00060   T offset;
00061   T drift;
00062   T drift_frequency;
00063   T gaussian_noise;
00064 
00065 private:
00066   T current_drift_;
00067   T current_error_;
00068 };
00069 
00070 template <typename T>
00071 SensorModel_<T>::SensorModel_()
00072   : offset()
00073   , drift()
00074   , drift_frequency()
00075   , gaussian_noise()
00076 {
00077   drift_frequency = 1.0/3600.0;
00078   reset();
00079 }
00080 
00081 template <typename T>
00082 SensorModel_<T>::~SensorModel_()
00083 {
00084 }
00085 
00086 template <typename T>
00087 void SensorModel_<T>::Load(sdf::ElementPtr _sdf, const std::string& prefix)
00088 {
00089   std::string _offset, _drift, _drift_frequency, _gaussian_noise;
00090 
00091   if (prefix.empty()) {
00092     _offset          = "offset";
00093     _drift           = "drift";
00094     _drift_frequency = "driftFrequency";
00095     _gaussian_noise  = "gaussianNoise";
00096   } else {
00097     _offset          = prefix + "Offset";
00098     _drift           = prefix + "Drift";
00099     _drift_frequency = prefix + "DriftFrequency";
00100     _gaussian_noise  = prefix + "GaussianNoise";
00101   }
00102 
00103   if (_sdf->HasElement(_offset))          LoadImpl(_sdf->GetElement(_offset), offset);
00104   if (_sdf->HasElement(_drift))           LoadImpl(_sdf->GetElement(_drift), drift);
00105   if (_sdf->HasElement(_drift_frequency)) LoadImpl(_sdf->GetElement(_drift_frequency), drift_frequency);
00106   if (_sdf->HasElement(_gaussian_noise))  LoadImpl(_sdf->GetElement(_gaussian_noise), gaussian_noise);
00107 }
00108 
00109 template <typename T>
00110 bool SensorModel_<T>::LoadImpl(sdf::ElementPtr _element, T& _value) {
00111   if (!_element->GetValue()) return false;
00112   return _element->GetValue()->Get(_value);
00113 }
00114 
00115 namespace {
00116   template <typename T>
00117   static inline T SensorModelGaussianKernel(T mu, T sigma)
00118   {
00119     // using Box-Muller transform to generate two independent standard normally disbributed normal variables
00120     // see wikipedia
00121     T U = (T)rand()/(T)RAND_MAX; // normalized uniform random variable
00122     T V = (T)rand()/(T)RAND_MAX; // normalized uniform random variable
00123     T X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
00124     X = sigma * X + mu;
00125     return X;
00126   }
00127 
00128   template <typename T>
00129   static inline T SensorModelInternalUpdate(T& current_drift, T drift, T drift_frequency, T offset, T gaussian_noise, double dt)
00130   {
00131     current_drift = current_drift - dt * (current_drift * drift_frequency + SensorModelGaussianKernel(T(), sqrt(2*drift_frequency)*drift));
00132     return offset + current_drift + SensorModelGaussianKernel(T(), gaussian_noise);
00133   }
00134 }
00135 
00136 template <typename T>
00137 T SensorModel_<T>::update(double dt)
00138 {
00139   for(std::size_t i = 0; i < current_error_.size(); ++i) current_error_[i] = current_error_ = SensorModelInternalUpdate(current_drift_[i], drift[i], drift_frequency[i], offset[i], gaussian_noise[i], dt);
00140   return current_error_;
00141 }
00142 
00143 template <>
00144 double SensorModel_<double>::update(double dt)
00145 {
00146   current_error_ = SensorModelInternalUpdate(current_drift_, drift, drift_frequency, offset, gaussian_noise, dt);
00147   return current_error_;
00148 }
00149 
00150 template <>
00151 math::Vector3 SensorModel_<math::Vector3>::update(double dt)
00152 {
00153   current_error_.x = SensorModelInternalUpdate(current_drift_.x, drift.x, drift_frequency.x, offset.x, gaussian_noise.x, dt);
00154   current_error_.y = SensorModelInternalUpdate(current_drift_.y, drift.y, drift_frequency.y, offset.y, gaussian_noise.y, dt);
00155   current_error_.z = SensorModelInternalUpdate(current_drift_.z, drift.z, drift_frequency.z, offset.z, gaussian_noise.z, dt);
00156   return current_error_;
00157 }
00158 
00159 template <typename T>
00160 void SensorModel_<T>::reset(const T& value)
00161 {
00162   current_drift_ = T();
00163   current_error_ = value;
00164 }
00165 
00166 typedef SensorModel_<double> SensorModel;
00167 typedef SensorModel_<math::Vector3> SensorModel3;
00168 
00169 }
00170 
00171 #endif // HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H


husky_gazebo_plugins
Author(s):
autogenerated on Wed Aug 26 2015 11:54:19