1 #ifndef PCL_TRACKING_IMPL_TRACKING_H_
2 #define PCL_TRACKING_IMPL_TRACKING_H_
4 #include <pcl/common/eigen.h>
5 #include <pcl/tracking/tracking.h>
28 x = y = z = roll = pitch = yaw = 0.0;
37 roll = pitch = yaw = 0.0;
42 float _x,
float _y,
float _z,
float _roll,
float _pitch,
float _yaw)
60 sample(
const std::vector<double>& mean,
const std::vector<double>& cov)
77 Eigen::Matrix3f current_rotation;
79 Eigen::Quaternionf q_current_rotation(current_rotation);
81 Eigen::Matrix3f mean_rotation;
85 Eigen::Quaternionf q_mean_rotation(mean_rotation);
89 constexpr
float scale_factor = 0.2862;
95 Eigen::Vector4f vec_sample_mean_0(a, b, c, 1);
96 Eigen::Quaternionf q_sample_mean_0(vec_sample_mean_0);
97 q_sample_mean_0.normalize();
99 Eigen::Quaternionf q_sample_user_mean =
100 q_sample_mean_0 * q_mean_rotation * q_current_rotation;
102 Eigen::Affine3f affine_R(q_sample_user_mean.toRotationMatrix());
117 inline Eigen::Affine3f
126 float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
128 trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
129 return {trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw};
132 template <
class InputIterator>
137 float wa_roll_sin = 0.0, wa_roll_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0,
138 wa_yaw_sin = 0.0, wa_yaw_cos = 0.0;
139 for (
auto point = first; point != last; ++point) {
140 wa.x += point->x * point->
weight;
141 wa.y += point->y * point->
weight;
142 wa.z += point->z * point->
weight;
143 wa_pitch_cos = std::cos(point->pitch);
144 wa_roll_sin += wa_pitch_cos * std::sin(point->roll) * point->weight;
145 wa_roll_cos += wa_pitch_cos * std::cos(point->roll) * point->weight;
146 wa_pitch_sin += std::sin(point->pitch) * point->weight;
147 wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight;
148 wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight;
150 wa.
roll = std::atan2(wa_roll_sin, wa_roll_cos);
151 wa.
pitch = std::asin(wa_pitch_sin);
152 wa.
yaw = std::atan2(wa_yaw_sin, wa_yaw_cos);
184 os <<
"(" << p.x <<
"," << p.y <<
"," << p.z <<
"," << p.
roll <<
"," << p.
pitch <<
","
190 inline ParticleXYZRPY
194 newp.x =
static_cast<float>(p.x * val);
195 newp.y =
static_cast<float>(p.y * val);
196 newp.z =
static_cast<float>(p.z * val);
197 newp.
roll =
static_cast<float>(p.
roll * val);
198 newp.
pitch =
static_cast<float>(p.
pitch * val);
199 newp.
yaw =
static_cast<float>(p.
yaw * val);
204 inline ParticleXYZRPY
218 inline ParticleXYZRPY
255 x = y = z = roll = pitch = yaw = 0.0;
264 roll = pitch = yaw = 0.0;
268 inline ParticleXYZR(
float _x,
float _y,
float _z,
float,
float _pitch,
float)
286 sample(
const std::vector<double>& mean,
const std::vector<double>& cov)
292 pitch +=
static_cast<float>(
sampleNormal(mean[4], cov[4]));
307 inline Eigen::Affine3f
316 float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
318 trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
319 return {trans_x, trans_y, trans_z, 0, trans_pitch, 0};
322 template <
class InputIterator>
327 float wa_pitch_sin = 0.0;
328 for (
auto point = first; point != last; ++point) {
329 wa.x += point->x * point->
weight;
330 wa.y += point->y * point->
weight;
331 wa.z += point->z * point->
weight;
332 wa_pitch_sin += std::sin(point->pitch) * point->weight;
335 wa.
pitch = std::asin(wa_pitch_sin);
368 os <<
"(" << p.x <<
"," << p.y <<
"," << p.z <<
"," << p.
roll <<
"," << p.
pitch <<
","
378 newp.x =
static_cast<float>(p.x * val);
379 newp.y =
static_cast<float>(p.y * val);
380 newp.z =
static_cast<float>(p.z * val);
381 newp.
roll =
static_cast<float>(p.
roll * val);
382 newp.
pitch =
static_cast<float>(p.
pitch * val);
383 newp.
yaw =
static_cast<float>(p.
yaw * val);
439 x = y = z = roll = pitch = yaw = 0.0;
448 roll = pitch = yaw = 0.0;
452 inline ParticleXYRPY(
float _x,
float,
float _z,
float _roll,
float _pitch,
float _yaw)
470 sample(
const std::vector<double>& mean,
const std::vector<double>& cov)
475 roll +=
static_cast<float>(
sampleNormal(mean[3], cov[3]));
476 pitch +=
static_cast<float>(
sampleNormal(mean[4], cov[4]));
477 yaw +=
static_cast<float>(
sampleNormal(mean[5], cov[5]));
491 inline Eigen::Affine3f
500 float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
502 trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
503 return {trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw};
506 template <
class InputIterator>
511 float wa_roll_sin = 0.0, wa_roll_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0,
512 wa_yaw_sin = 0.0, wa_yaw_cos = 0.0;
513 for (
auto point = first; point != last; ++point) {
514 wa.x += point->x * point->
weight;
515 wa.z += point->z * point->
weight;
516 wa_pitch_cos = std::cos(point->pitch);
517 wa_roll_sin += wa_pitch_cos * std::sin(point->roll) * point->weight;
518 wa_roll_cos += wa_pitch_cos * std::cos(point->roll) * point->weight;
519 wa_pitch_sin += std::sin(point->pitch) * point->weight;
520 wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight;
521 wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight;
524 wa.
roll = std::atan2(wa_roll_sin, wa_roll_cos);
525 wa.
pitch = std::asin(wa_pitch_sin);
526 wa.
yaw = std::atan2(wa_yaw_sin, wa_yaw_cos);
558 os <<
"(" << p.x <<
"," << p.y <<
"," << p.z <<
"," << p.
roll <<
"," << p.
pitch <<
","
568 newp.x =
static_cast<float>(p.x * val);
569 newp.y =
static_cast<float>(p.y * val);
570 newp.z =
static_cast<float>(p.z * val);
571 newp.
roll =
static_cast<float>(p.
roll * val);
572 newp.
pitch =
static_cast<float>(p.
pitch * val);
573 newp.
yaw =
static_cast<float>(p.
yaw * val);
629 x = y = z = roll = pitch = yaw = 0.0;
638 roll = pitch = yaw = 0.0;
642 inline ParticleXYRP(
float _x,
float,
float _z,
float,
float _pitch,
float _yaw)
660 sample(
const std::vector<double>& mean,
const std::vector<double>& cov)
666 pitch +=
static_cast<float>(
sampleNormal(mean[4], cov[4]));
667 yaw +=
static_cast<float>(
sampleNormal(mean[5], cov[5]));
681 inline Eigen::Affine3f
690 float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
692 trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
693 return {trans_x, 0, trans_z, 0, trans_pitch, trans_yaw};
696 template <
class InputIterator>
701 float wa_yaw_sin = 0.0, wa_yaw_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0;
702 for (
auto point = first; point != last; ++point) {
703 wa.x += point->x * point->
weight;
704 wa.z += point->z * point->
weight;
705 wa_pitch_cos = std::cos(point->pitch);
706 wa_pitch_sin += std::sin(point->pitch) * point->weight;
707 wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight;
708 wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight;
712 wa.
pitch = std::asin(wa_pitch_sin);
713 wa.
yaw = std::atan2(wa_yaw_sin, wa_yaw_cos);
745 os <<
"(" << p.x <<
"," << p.y <<
"," << p.z <<
"," << p.
roll <<
"," << p.
pitch <<
","
755 newp.x =
static_cast<float>(p.x * val);
756 newp.y =
static_cast<float>(p.y * val);
757 newp.z =
static_cast<float>(p.z * val);
758 newp.
roll =
static_cast<float>(p.
roll * val);
759 newp.
pitch =
static_cast<float>(p.
pitch * val);
760 newp.
yaw =
static_cast<float>(p.
yaw * val);
816 x = y = z = roll = pitch = yaw = 0.0;
825 roll = pitch = yaw = 0.0;
829 inline ParticleXYR(
float _x,
float,
float _z,
float,
float _pitch,
float)
847 sample(
const std::vector<double>& mean,
const std::vector<double>& cov)
853 pitch +=
static_cast<float>(
sampleNormal(mean[4], cov[4]));
868 inline Eigen::Affine3f
877 float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
879 trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
880 return {trans_x, 0, trans_z, 0, trans_pitch, 0};
883 template <
class InputIterator>
888 float wa_pitch_sin = 0.0;
889 for (
auto point = first; point != last; ++point) {
890 wa.x += point->x * point->
weight;
891 wa.z += point->z * point->
weight;
892 wa_pitch_sin += std::sin(point->pitch) * point->weight;
896 wa.
pitch = std::asin(wa_pitch_sin);
929 os <<
"(" << p.x <<
"," << p.y <<
"," << p.z <<
"," << p.
roll <<
"," << p.
pitch <<
","
939 newp.x =
static_cast<float>(p.x * val);
940 newp.y =
static_cast<float>(p.y * val);
941 newp.z =
static_cast<float>(p.z * val);
942 newp.
roll =
static_cast<float>(p.
roll * val);
943 newp.
pitch =
static_cast<float>(p.
pitch * val);
944 newp.
yaw =
static_cast<float>(p.
yaw * val);
979 #define PCL_STATE_POINT_TYPES \
980 (pcl::tracking::ParticleXYR)(pcl::tracking::ParticleXYZRPY)( \
981 pcl::tracking::ParticleXYZR)(pcl::tracking::ParticleXYRPY)( \
982 pcl::tracking::ParticleXYRP)
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
void getTranslationAndEulerAngles(const Eigen::Transform< Scalar, 3, Eigen::Affine > &t, Scalar &x, Scalar &y, Scalar &z, Scalar &roll, Scalar &pitch, Scalar &yaw)
Extract x,y,z and the Euler angles (intrinsic rotations, ZYX-convention) from the given transformatio...
void getTransformation(Scalar x, Scalar y, Scalar z, Scalar roll, Scalar pitch, Scalar yaw, Eigen::Transform< Scalar, 3, Eigen::Affine > &t)
Create a transformation from the given translation and Euler angles (intrinsic rotations,...
void getEulerAngles(const Eigen::Transform< Scalar, 3, Eigen::Affine > &t, Scalar &roll, Scalar &pitch, Scalar &yaw)
Extract the Euler angles (intrinsic rotations, ZYX-convention) from the given transformation.
Defines functions, macros and traits for allocating and using memory.
PCL_EXPORTS double sampleNormal(double mean, double sigma)
ParticleXYZRPY operator*(const ParticleXYZRPY &p, double val)
std::ostream & operator<<(std::ostream &os, const ParticleXYZRPY &p)
ParticleXYZRPY operator-(const ParticleXYZRPY &a, const ParticleXYZRPY &b)
ParticleXYZRPY operator+(const ParticleXYZRPY &a, const ParticleXYZRPY &b)
Defines all the PCL and non-PCL macros used.
static ParticleXYR weightedAverage(InputIterator first, InputIterator last)
Eigen::Affine3f toEigenMatrix() const
static int stateDimension()
ParticleXYR(float _x, float, float _z, float, float _pitch, float)
float operator[](unsigned int i)
ParticleXYR(float _x, float, float _z)
void sample(const std::vector< double > &mean, const std::vector< double > &cov)
static ParticleXYR toState(const Eigen::Affine3f &trans)
static int stateDimension()
static ParticleXYRP weightedAverage(InputIterator first, InputIterator last)
void sample(const std::vector< double > &mean, const std::vector< double > &cov)
float operator[](unsigned int i)
Eigen::Affine3f toEigenMatrix() const
ParticleXYRP(float _x, float, float _z)
static ParticleXYRP toState(const Eigen::Affine3f &trans)
ParticleXYRP(float _x, float, float _z, float, float _pitch, float _yaw)
void sample(const std::vector< double > &mean, const std::vector< double > &cov)
static int stateDimension()
Eigen::Affine3f toEigenMatrix() const
static ParticleXYRPY weightedAverage(InputIterator first, InputIterator last)
ParticleXYRPY(float _x, float, float _z)
static ParticleXYRPY toState(const Eigen::Affine3f &trans)
ParticleXYRPY(float _x, float, float _z, float _roll, float _pitch, float _yaw)
float operator[](unsigned int i)
Eigen::Affine3f toEigenMatrix() const
static int stateDimension()
ParticleXYZR(float _x, float _y, float _z, float, float _pitch, float)
static ParticleXYZR toState(const Eigen::Affine3f &trans)
void sample(const std::vector< double > &mean, const std::vector< double > &cov)
ParticleXYZR(float _x, float _y, float _z)
float operator[](unsigned int i)
static ParticleXYZR weightedAverage(InputIterator first, InputIterator last)
static ParticleXYZRPY toState(const Eigen::Affine3f &trans)
static int stateDimension()
void sample(const std::vector< double > &mean, const std::vector< double > &cov)
static ParticleXYZRPY weightedAverage(InputIterator first, InputIterator last)
ParticleXYZRPY(float _x, float _y, float _z, float _roll, float _pitch, float _yaw)
Eigen::Affine3f toEigenMatrix() const
float operator[](unsigned int i)
ParticleXYZRPY(float _x, float _y, float _z)