30 #ifndef MCL_3DL_STATE_6DOF_H 31 #define MCL_3DL_STATE_6DOF_H 67 RPYVec(
const float r,
const float p,
const float y)
94 return odom_err_integ_lin_.
x_;
96 return odom_err_integ_lin_.
y_;
98 return odom_err_integ_lin_.
z_;
100 return odom_err_integ_ang_.
x_;
102 return odom_err_integ_ang_.
y_;
104 return odom_err_integ_ang_.
z_;
129 return odom_err_integ_lin_.
x_;
131 return odom_err_integ_lin_.
y_;
133 return odom_err_integ_lin_.
z_;
135 return odom_err_integ_ang_.
x_;
137 return odom_err_integ_ang_.
y_;
139 return odom_err_integ_ang_.
z_;
156 noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
164 noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
173 noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
182 template <
typename Po
intType>
186 for (
auto& p : pc.points)
195 std::default_random_engine& engine_,
201 ROS_ERROR(
"Failed to generate noise. mean must be mcl_3dl::Quat and sigma must be rpy vec.");
203 for (
size_t i = 0; i < 3; i++)
205 std::normal_distribution<float> nd(mean[i], sigma[i]);
206 noise[i] = noise[i + 7] = nd(engine_);
209 for (
size_t i = 0; i < 3; i++)
211 std::normal_distribution<float> nd(0.0, sigma.
rpy_.
v_[i]);
212 rpy_noise[i] = noise[i + 10] = nd(engine_);
221 for (
size_t i = 0; i <
size(); i++)
223 if (3 <= i && i <= 6)
225 ret[i] = (*this)[i] + in[i];
234 for (
size_t i = 0; i <
size(); i++)
236 if (3 <= i && i <= 6)
238 ret[i] = (*this)[i] - in[i];
252 : ParticleWeightedMean()
253 , front_sum_(0.0, 0.0, 0.0)
254 , up_sum_(0.0, 0.0, 0.0)
274 assert(p_sum_ > 0.0);
286 #endif // MCL_3DL_STATE_6DOF_H
void transform(pcl::PointCloud< PointType > &pc) const
float & operator[](const size_t i) override
State6DOF operator-(const State6DOF &a) const
float getTotalProbability()
mcl_3dl::Vec3 odom_err_integ_ang_
mcl_3dl::Vec3 odom_err_integ_lin_
State6DOF operator+(const State6DOF &a) const
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
geometry_msgs::TransformStamped t
void add(const State6DOF &s, const float &prob)
size_t size() const override
float operator[](const size_t i) const
RPYVec(const mcl_3dl::Vec3 &v)
ParticleWeightedMeanQuat()
void normalize() override
static State6DOF generateNoise(std::default_random_engine &engine_, const State6DOF &mean, const State6DOF &sigma)
RPYVec(const float r, const float p, const float y)
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)