21 enable_exception_on_undeterminate(false),
23 m_accum_x(0),m_accum_y(0)
28 m_accum_x=m_accum_y=.0;
31 append(orientation_rad,1.0);
35 m_accum_x += cos(orientation_rad) * weight;
36 m_accum_y += sin(orientation_rad) * weight;
41 const double x = m_accum_x / m_count;
42 const double y = m_accum_y / m_count;
44 double ang = atan2(
y,
x);
47 if (enable_exception_on_undeterminate)
48 throw std::runtime_error(
"[SO_average<2>::get_average()] Undetermined average value");
56 enable_exception_on_undeterminate(false),
64 m_accum_rot.setZero();
71 m_accum_rot += weight*M;
77 const Eigen::Matrix3d MtM = m_accum_rot.transpose() * m_accum_rot;
79 Eigen::JacobiSVD<Eigen::Matrix3d> svd(MtM, Eigen::ComputeFullU);
80 const Eigen::Vector3d vs = svd.singularValues();
83 const double d1 = 1.0/sqrt(vs[0]);
84 const double d2 = 1.0/sqrt(vs[1]);
88 if (enable_exception_on_undeterminate)
89 throw std::runtime_error(
"[SO_average<3>::get_average()] Undetermined average value");
90 else return Eigen::Matrix3d::Identity();
93 Eigen::Matrix3d D = Eigen::Matrix3d::Zero();
94 D(0,0)=d1; D(1,1)=d2; D(2,2)=d3;
95 Eigen::Matrix3d ret = m_accum_rot * svd.matrixU() * D * svd.matrixU().transpose();
101 enable_exception_on_undeterminate(false),
103 m_accum_x(0),m_accum_y(0),
110 m_accum_x=m_accum_y=.0;
118 m_accum_x += weight *
p.x();
119 m_accum_y += weight *
p.y();
120 m_rot_part.append(
p.phi(), weight);
125 ret_mean.
x( m_accum_x / m_count );
126 ret_mean.
y( m_accum_y / m_count );
127 const_cast<SO_average<2>*
>(&m_rot_part)->enable_exception_on_undeterminate = this->enable_exception_on_undeterminate;
128 ret_mean.
phi ( m_rot_part.get_average() );
133 enable_exception_on_undeterminate(false),
135 m_accum_x(0),m_accum_y(0),m_accum_z(0),
142 m_accum_x=m_accum_y=m_accum_z=.0;
150 m_accum_x += weight *
p.x();
151 m_accum_y += weight *
p.y();
152 m_accum_z += weight *
p.z();
153 m_rot_part.append(
p.getRotationMatrix(), weight);
158 ret_mean.
x( m_accum_x / m_count );
159 ret_mean.
y( m_accum_y / m_count );
160 ret_mean.z( m_accum_z / m_count );
161 const_cast<SO_average<3>*
>(&m_rot_part)->enable_exception_on_undeterminate = this->enable_exception_on_undeterminate;
double x() const
Common members of all points & poses classes.
void append(const mrpt::poses::CPose3D &p)
Adds a new pose to the computation.
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.
class BASE_IMPEXP SE_average
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
#define ASSERT_ABOVE_(__A, __B)
class BASE_IMPEXP SO_average
Computes weighted and un-weighted averages of SO(2) or SO(3) orientations.
int sign(T x)
Returns the sign of X as "1" or "-1".
void append(const mrpt::poses::CPose2D &p)
Adds a new pose to the computation.
void append(const double orientation_rad)
Adds a new orientation (radians) to the computation.
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.
void append(const Eigen::Matrix3d &M)
Adds a new orientation to the computation.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double get_average() const
Returns the average orientation (radians).
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void get_average(mrpt::poses::CPose3D &out_mean) const
Returns the average pose.
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).
Eigen::Matrix3d get_average() const
Returns the average orientation.
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Computes weighted and un-weighted averages of SO(3) orientations.
void get_average(mrpt::poses::CPose2D &out_mean) const
Returns the average pose.