Go to the documentation of this file.
30 #ifndef MCL_3DL_STATE_6DOF_H
31 #define MCL_3DL_STATE_6DOF_H
72 RPYVec(
const float r,
const float p,
const float y)
166 float val = 1.0f, diff = 0.0f;
167 for (
size_t i : {j, k})
171 diff = (*this)[i] - e[i];
175 diff = rpy[i - 3] - exp_rpy[i - 3];
214 template <
typename Po
intType>
218 for (
auto& p : pc.points)
226 template <
typename T,
typename RANDOM_ENGINE,
typename NOISE_GEN>
229 if (gen.getDimension() != 6)
231 ROS_ERROR(
"Dimension of noise must be 6. Passed: %lu", gen.getDimension());
234 const std::vector<float> org_noise = gen(engine);
235 const std::vector<float>& mean = gen.getMean();
236 for (
size_t i = 0; i < 3; i++)
238 noise[i] = noise[i + 7] = org_noise[i];
241 for (
size_t i = 0; i < 3; i++)
243 rpy_noise[i] = org_noise[i + 3];
244 noise[i + 10] = org_noise[i + 3] - mean[i + 3];
253 for (
size_t i = 0; i <
size(); i++)
255 if (3 <= i && i <= 6)
257 ret[i] = (*this)[i] + in[i];
266 for (
size_t i = 0; i <
size(); i++)
268 if (3 <= i && i <= 6)
270 ret[i] = (*this)[i] - in[i];
284 ROS_ERROR(
"Failed to generate noise. mean must be mcl_3dl::Quat.");
286 for (
size_t i = 0; i < 3; i++)
291 for (
size_t i = 0; i < 3; i++)
293 mean_[i + 3] = rpy[i];
304 ROS_ERROR(
"Failed to generate noise. sigma must be rpy vec.");
306 for (
size_t i = 0; i < 3; i++)
308 sigma_[i] = sigma[i];
310 for (
size_t i = 0; i < 3; i++)
312 sigma_[i + 3] = sigma.
rpy_.
v_[i];
358 #endif // MCL_3DL_STATE_6DOF_H
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
void setSigma(const T &sigma)
mcl_3dl::Vec3 odom_err_integ_ang_
constexpr Quat inv() const
void transform(pcl::PointCloud< PointType > &pc) const
void setMean(const T &mean)
RPYVec(const float r, const float p, const float y)
constexpr Vec3 getRPY() const
float & operator[](const size_t i) override
void normalize() override
mcl_3dl::Vec3 odom_err_integ_lin_
float operator[](const size_t i) const
size_t size() const override
State6DOF operator-(const State6DOF &a) const
size_t covDimension() const override
void add(const State6DOF &s, const float &prob)
float covElement(const State6DOF &e, const size_t &j, const size_t &k)
float getTotalProbability()
ParticleWeightedMeanQuat()
static State6DOF generateNoise(RANDOM_ENGINE &engine, const NOISE_GEN &gen)
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
State6DOF operator+(const State6DOF &a) const
geometry_msgs::TransformStamped t
RPYVec(const mcl_3dl::Vec3 &v)
mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04