$search
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 <gazebo/Param.hh> 00033 00034 namespace gazebo { 00035 00036 template <typename T> 00037 class SensorModel_ { 00038 public: 00039 SensorModel_(std::vector<Param*> ¶meters, const std::string& prefix = ""); 00040 virtual ~SensorModel_(); 00041 00042 virtual void Load(XMLConfigNode *node); 00043 00044 virtual T operator()(const T& value) const { return value + current_error_; } 00045 virtual T operator()(const T& value, double dt) { return value + update(dt); } 00046 00047 virtual T update(double dt); 00048 virtual void reset(const T& value = T()); 00049 00050 virtual const T& getCurrentError() const { return current_error_; } 00051 virtual const T& getCurrentDrift() const { return current_drift_; } 00052 00053 virtual void setCurrentDrift(const T& new_drift) { current_drift_ = new_drift; } 00054 00055 public: 00056 T offset; 00057 T drift; 00058 T drift_frequency; 00059 T gaussian_noise; 00060 00061 private: 00062 ParamT<T> *offset_param_; 00063 ParamT<T> *drift_param_; 00064 ParamT<T> *drift_frequency_param_; 00065 ParamT<T> *gaussian_noise_param_; 00066 00067 static T Value(double value); 00068 00069 T current_drift_; 00070 T current_error_; 00071 }; 00072 00073 template <typename T> 00074 SensorModel_<T>::SensorModel_(std::vector<Param*> ¶meters, const std::string &prefix) 00075 { 00076 Param::Begin(¶meters); 00077 if (prefix.empty()) { 00078 offset_param_ = new ParamT<T>("offset", Value(0.0), 0); 00079 drift_param_ = new ParamT<T>("drift", Value(0.0), 0); 00080 drift_frequency_param_ = new ParamT<T>("driftFrequency", Value(1.0/3600.0), 0); 00081 gaussian_noise_param_ = new ParamT<T>("gaussianNoise", Value(0.0), 0); 00082 } else { 00083 offset_param_ = new ParamT<T>(prefix + "Offset", Value(0.0), 0); 00084 drift_param_ = new ParamT<T>(prefix + "Drift", Value(0.0), 0); 00085 drift_frequency_param_ = new ParamT<T>(prefix + "DriftFrequency", Value(1.0/3600.0), 0); 00086 gaussian_noise_param_ = new ParamT<T>(prefix + "GaussianNoise", Value(0.0), 0); 00087 } 00088 Param::End(); 00089 00090 reset(); 00091 } 00092 00093 template <typename T> 00094 SensorModel_<T>::~SensorModel_() 00095 { 00096 delete offset_param_; 00097 delete drift_param_; 00098 delete drift_frequency_param_; 00099 delete gaussian_noise_param_; 00100 } 00101 00102 template <typename T> 00103 void SensorModel_<T>::Load(XMLConfigNode *node) 00104 { 00105 offset_param_->Load(node); 00106 offset = offset_param_->GetValue(); 00107 drift_param_->Load(node); 00108 drift = drift_param_->GetValue(); 00109 drift_frequency_param_->Load(node); 00110 drift_frequency = drift_frequency_param_->GetValue(); 00111 gaussian_noise_param_->Load(node); 00112 gaussian_noise = gaussian_noise_param_->GetValue(); 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 Vector3 SensorModel_<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 template <typename T> T SensorModel_<T>::Value(double value) { return T(value); } 00167 template <> Vector3 SensorModel_<Vector3>::Value(double value) { return Vector3(value, value, value); } 00168 00169 typedef SensorModel_<double> SensorModel; 00170 typedef SensorModel_<Vector3> SensorModel3; 00171 00172 } 00173 00174 #endif // HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H