21 : enable_exception_on_undeterminate(false),
30 m_accum_x = m_accum_y = .0;
34 append(orientation_rad, 1.0);
39 m_accum_x += cos(orientation_rad) * weight;
40 m_accum_y += sin(orientation_rad) * weight;
45 const double x = m_accum_x / m_count;
46 const double y = m_accum_y / m_count;
48 double ang = atan2(
y,
x);
51 if (enable_exception_on_undeterminate)
52 throw std::runtime_error(
53 "[SO_average<2>::get_average()] Undetermined average value");
62 : enable_exception_on_undeterminate(false), m_count(0), m_accum_rot()
69 m_accum_rot.setZero();
75 m_accum_rot += weight * M;
82 const Eigen::Matrix3d MtM = m_accum_rot.transpose() * m_accum_rot;
84 Eigen::JacobiSVD<Eigen::Matrix3d> svd(MtM, Eigen::ComputeFullU);
85 const Eigen::Vector3d vs = svd.singularValues();
88 const double d1 = 1.0 / sqrt(vs[0]);
89 const double d2 = 1.0 / sqrt(vs[1]);
94 if (enable_exception_on_undeterminate)
95 throw std::runtime_error(
96 "[SO_average<3>::get_average()] Undetermined average value");
98 return Eigen::Matrix3d::Identity();
101 Eigen::Matrix3d D = Eigen::Matrix3d::Zero();
105 Eigen::Matrix3d ret =
106 m_accum_rot * svd.matrixU() * D * svd.matrixU().transpose();
112 : enable_exception_on_undeterminate(false),
123 m_accum_x = m_accum_y = .0;
130 m_accum_x += weight *
p.x();
131 m_accum_y += weight *
p.y();
132 m_rot_part.append(
p.phi(), weight);
137 ret_mean.
x(m_accum_x / m_count);
138 ret_mean.
y(m_accum_y / m_count);
139 const_cast<SO_average<2>*
>(&m_rot_part)->enable_exception_on_undeterminate =
140 this->enable_exception_on_undeterminate;
141 ret_mean.
phi(m_rot_part.get_average());
146 : enable_exception_on_undeterminate(false),
158 m_accum_x = m_accum_y = m_accum_z = .0;
165 m_accum_x += weight *
p.x();
166 m_accum_y += weight *
p.y();
167 m_accum_z += weight *
p.z();
168 m_rot_part.append(
p.getRotationMatrix(), weight);
173 ret_mean.
x(m_accum_x / m_count);
174 ret_mean.
y(m_accum_y / m_count);
175 ret_mean.z(m_accum_z / m_count);
176 const_cast<SO_average<3>*
>(&m_rot_part)->enable_exception_on_undeterminate =
177 this->enable_exception_on_undeterminate;
double x() const
Common members of all points & poses classes.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Computes weighted and un-weighted averages of SO(2) orientations.
#define ASSERT_ABOVE_(__A, __B)
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
int sign(T x)
Returns the sign of X as "1" or "-1".
void clear()
Clear the contents of this container.
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
Sets the 3x3 rotation matrix.
This base provides a set of functions for maths stuff.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Computes weighted and un-weighted averages of SO(3) orientations.
Computes weighted and un-weighted averages of SO(2) or SO(3) orientations.