Go to the documentation of this file.
49 void append(
const double orientation_rad);
52 void append(
const double orientation_rad,
const double weight);
60 double get_average()
const;
63 bool enable_exception_on_undeterminate{
false};
67 double m_accum_x{0}, m_accum_y{0};
104 bool enable_exception_on_undeterminate{
false};
141 bool enable_exception_on_undeterminate{
false};
145 double m_accum_x{0}, m_accum_y{0};
179 bool enable_exception_on_undeterminate{
false};
183 double m_accum_x{0}, m_accum_y{0}, m_accum_z{0};
void clear()
Clear the contents of this container.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Computes weighted and un-weighted averages of SO(2) orientations.
SO_average< 2 > m_rot_part
Computes weighted and un-weighted averages of SO(2) or SO(3) orientations.
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).
mrpt::math::CMatrixDouble33 m_accum_rot
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
SO_average< 3 > m_rot_part
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
Computes weighted and un-weighted averages of SO(3) orientations.
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Sun Jul 19 15:15:43 UTC 2020 | |