29 #ifndef HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H 30 #define HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H 33 #if (GAZEBO_MAJOR_VERSION < 8) 34 #include <gazebo/math/Vector3.hh> 37 #include <hector_gazebo_plugins/SensorModelConfig.h> 42 using hector_gazebo_plugins::SensorModelConfig;
50 virtual void Load(sdf::ElementPtr _sdf,
const std::string& prefix = std::string());
55 virtual T
update(
double dt);
57 virtual void reset(
const T& value);
69 virtual bool LoadImpl(sdf::ElementPtr _element, T& _value);
100 template <
typename T>
103 std::string _offset, _drift, _drift_frequency, _gaussian_noise, _scale_error;
105 if (prefix.empty()) {
108 _drift_frequency =
"driftFrequency";
109 _gaussian_noise =
"gaussianNoise";
110 _scale_error =
"scaleError";
112 _offset = prefix +
"Offset";
113 _drift = prefix +
"Drift";
114 _drift_frequency = prefix +
"DriftFrequency";
115 _gaussian_noise = prefix +
"GaussianNoise";
116 _scale_error = prefix +
"ScaleError";
119 if (_sdf->HasElement(_offset))
LoadImpl(_sdf->GetElement(_offset),
offset);
120 if (_sdf->HasElement(_drift))
LoadImpl(_sdf->GetElement(_drift),
drift);
128 template <
typename T>
130 if (!_element->GetValue())
return false;
131 return _element->GetValue()->Get(_value);
135 template <
typename T>
136 static inline T SensorModelGaussianKernel(T mu, T sigma)
140 T U = (T)rand()/(T)RAND_MAX;
141 T V = (T)rand()/(T)RAND_MAX;
142 T X = sqrt(-2.0 * ::log(U)) * cos( 2.0*M_PI * V);
147 template <
typename T>
151 current_drift = exp(-dt * drift_frequency) * current_drift + dt * SensorModelGaussianKernel(T(), sqrt(2*drift_frequency)*drift);
152 return offset + current_drift + SensorModelGaussianKernel(T(), gaussian_noise);
156 template <
typename T>
170 #if (GAZEBO_MAJOR_VERSION >= 8) 190 template <
typename T>
204 #if (GAZEBO_MAJOR_VERSION >= 8) 224 template <
typename T>
233 template <
typename T>
struct scalar_value<
std::vector<T> > {
static double toDouble(
const std::vector<T> &orig) {
return (
double) std::accumulate(orig.begin(), orig.end()) / orig.size(); } };
234 #if (GAZEBO_MAJOR_VERSION >= 8) 235 template <>
struct scalar_value<ignition::math::Vector3d> {
static double toDouble(
const ignition::math::Vector3d &orig) {
return (orig.X() + orig.Y() + orig.Z()) / 3; } };
241 template <
typename T>
247 drift = config.drift;
260 #if (GAZEBO_MAJOR_VERSION >= 8) 268 #endif // HECTOR_GAZEBO_PLUGINS_SENSOR_MODEL_H virtual const T & getCurrentDrift() const
virtual T update(double dt)
virtual void setCurrentDrift(const T &new_drift)
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix=std::string())
virtual T operator()(const T &value) const
virtual T getCurrentBias() const
virtual T operator()(const T &value, double dt)
virtual bool LoadImpl(sdf::ElementPtr _element, T &_value)
virtual void dynamicReconfigureCallback(SensorModelConfig &config, uint32_t level)
TFSIMD_FORCE_INLINE Vector3()
SensorModel_< math::Vector3 > SensorModel3
static double toDouble(const T &orig)
SensorModel_< double > SensorModel
static double toDouble(const math::Vector3 &orig)
virtual const T & getCurrentError() const
static double toDouble(const std::vector< T > &orig)
virtual const T & getScaleError() const