Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef MCL_3DL_STATE_6DOF_H
00031 #define MCL_3DL_STATE_6DOF_H
00032
00033 #include <algorithm>
00034
00035 #include <ros/ros.h>
00036
00037 #include <mcl_3dl/pf.h>
00038 #include <mcl_3dl/point_types.h>
00039 #include <mcl_3dl/quat.h>
00040 #include <mcl_3dl/vec3.h>
00041
00042 namespace mcl_3dl
00043 {
00044 class State6DOF : public mcl_3dl::pf::ParticleBase<float>
00045 {
00046 public:
00047 mcl_3dl::Vec3 pos_;
00048 mcl_3dl::Quat rot_;
00049 bool diff_;
00050 float noise_ll_;
00051 float noise_la_;
00052 float noise_al_;
00053 float noise_aa_;
00054 mcl_3dl::Vec3 odom_err_integ_lin_;
00055 mcl_3dl::Vec3 odom_err_integ_ang_;
00056 class RPYVec
00057 {
00058 public:
00059 mcl_3dl::Vec3 v_;
00060 RPYVec()
00061 {
00062 }
00063 explicit RPYVec(const mcl_3dl::Vec3& v)
00064 {
00065 v_ = v;
00066 }
00067 RPYVec(const float r, const float p, const float y)
00068 {
00069 v_.x_ = r;
00070 v_.y_ = p;
00071 v_.z_ = y;
00072 }
00073 };
00074 RPYVec rpy;
00075 float& operator[](const size_t i)override
00076 {
00077 switch (i)
00078 {
00079 case 0:
00080 return pos_.x_;
00081 case 1:
00082 return pos_.y_;
00083 case 2:
00084 return pos_.z_;
00085 case 3:
00086 return rot_.x_;
00087 case 4:
00088 return rot_.y_;
00089 case 5:
00090 return rot_.z_;
00091 case 6:
00092 return rot_.w_;
00093 case 7:
00094 return odom_err_integ_lin_.x_;
00095 case 8:
00096 return odom_err_integ_lin_.y_;
00097 case 9:
00098 return odom_err_integ_lin_.z_;
00099 case 10:
00100 return odom_err_integ_ang_.x_;
00101 case 11:
00102 return odom_err_integ_ang_.y_;
00103 case 12:
00104 return odom_err_integ_ang_.z_;
00105 default:
00106 assert(false);
00107 }
00108 return pos_.x_;
00109 }
00110 float operator[](const size_t i) const
00111 {
00112 switch (i)
00113 {
00114 case 0:
00115 return pos_.x_;
00116 case 1:
00117 return pos_.y_;
00118 case 2:
00119 return pos_.z_;
00120 case 3:
00121 return rot_.x_;
00122 case 4:
00123 return rot_.y_;
00124 case 5:
00125 return rot_.z_;
00126 case 6:
00127 return rot_.w_;
00128 case 7:
00129 return odom_err_integ_lin_.x_;
00130 case 8:
00131 return odom_err_integ_lin_.y_;
00132 case 9:
00133 return odom_err_integ_lin_.z_;
00134 case 10:
00135 return odom_err_integ_ang_.x_;
00136 case 11:
00137 return odom_err_integ_ang_.y_;
00138 case 12:
00139 return odom_err_integ_ang_.z_;
00140 default:
00141 assert(false);
00142 }
00143 return 0;
00144 }
00145 size_t size() const override
00146 {
00147 return 13;
00148 }
00149 void normalize() override
00150 {
00151 rot_.normalize();
00152 }
00153 State6DOF()
00154 {
00155 diff_ = false;
00156 noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
00157 odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
00158 odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
00159 }
00160 State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
00161 {
00162 pos_ = pos;
00163 rot_ = rot;
00164 noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
00165 odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
00166 odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
00167 diff_ = false;
00168 }
00169 State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
00170 {
00171 pos_ = pos;
00172 this->rpy = RPYVec(rpy);
00173 noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
00174 odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
00175 odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
00176 diff_ = true;
00177 }
00178 bool isDiff() const
00179 {
00180 return diff_;
00181 }
00182 template <typename PointType>
00183 void transform(pcl::PointCloud<PointType>& pc) const
00184 {
00185 const auto r = rot_.normalized();
00186 for (auto& p : pc.points)
00187 {
00188 const Vec3 t = r * Vec3(p.x, p.y, p.z) + pos_;
00189 p.x = t.x_;
00190 p.y = t.y_;
00191 p.z = t.z_;
00192 }
00193 }
00194 static State6DOF generateNoise(
00195 std::default_random_engine& engine_,
00196 const State6DOF& mean, const State6DOF& sigma)
00197 {
00198 State6DOF noise;
00199 if (mean.isDiff() || !sigma.isDiff())
00200 {
00201 ROS_ERROR("Failed to generate noise. mean must be mcl_3dl::Quat and sigma must be rpy vec.");
00202 }
00203 for (size_t i = 0; i < 3; i++)
00204 {
00205 std::normal_distribution<float> nd(mean[i], sigma[i]);
00206 noise[i] = noise[i + 7] = nd(engine_);
00207 }
00208 mcl_3dl::Vec3 rpy_noise;
00209 for (size_t i = 0; i < 3; i++)
00210 {
00211 std::normal_distribution<float> nd(0.0, sigma.rpy.v_[i]);
00212 rpy_noise[i] = noise[i + 10] = nd(engine_);
00213 }
00214 noise.rot_ = mcl_3dl::Quat(rpy_noise) * mean.rot_;
00215 return noise;
00216 }
00217 State6DOF operator+(const State6DOF& a) const
00218 {
00219 State6DOF in = a;
00220 State6DOF ret;
00221 for (size_t i = 0; i < size(); i++)
00222 {
00223 if (3 <= i && i <= 6)
00224 continue;
00225 ret[i] = (*this)[i] + in[i];
00226 }
00227 ret.rot_ = a.rot_ * rot_;
00228 return ret;
00229 }
00230 State6DOF operator-(const State6DOF& a) const
00231 {
00232 State6DOF in = a;
00233 State6DOF ret;
00234 for (size_t i = 0; i < size(); i++)
00235 {
00236 if (3 <= i && i <= 6)
00237 continue;
00238 ret[i] = (*this)[i] - in[i];
00239 }
00240 ret.rot_ = a.rot_ * rot_.inv();
00241 return ret;
00242 }
00243 };
00244 class ParticleWeightedMeanQuat : public mcl_3dl::pf::ParticleWeightedMean<State6DOF, float>
00245 {
00246 protected:
00247 mcl_3dl::Vec3 front_sum_;
00248 mcl_3dl::Vec3 up_sum_;
00249
00250 public:
00251 ParticleWeightedMeanQuat()
00252 : ParticleWeightedMean()
00253 , front_sum_(0.0, 0.0, 0.0)
00254 , up_sum_(0.0, 0.0, 0.0)
00255 {
00256 }
00257
00258 void add(const State6DOF& s, const float& prob)
00259 {
00260 p_sum_ += prob;
00261
00262 State6DOF e1 = s;
00263 e_.pos_ += e1.pos_ * prob;
00264
00265 const mcl_3dl::Vec3 front = s.rot_ * mcl_3dl::Vec3(1.0, 0.0, 0.0) * prob;
00266 const mcl_3dl::Vec3 up = s.rot_ * mcl_3dl::Vec3(0.0, 0.0, 1.0) * prob;
00267
00268 front_sum_ += front;
00269 up_sum_ += up;
00270 }
00271
00272 State6DOF getMean()
00273 {
00274 assert(p_sum_ > 0.0);
00275
00276 return State6DOF(e_.pos_ / p_sum_, mcl_3dl::Quat(front_sum_, up_sum_));
00277 }
00278
00279 float getTotalProbability()
00280 {
00281 return p_sum_;
00282 }
00283 };
00284 }
00285
00286 #endif // MCL_3DL_STATE_6DOF_H