Go to the documentation of this file.
49 void append(
const double orientation_rad);
52 void append(
const double orientation_rad,
const double weight);
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 append(const double orientation_rad, const double weight)
Adds a new orientation (radians) to the weighted-average computation.
void append(const mrpt::poses::CPose2D &p, const double weight)
Adds a new pose to the weighted-average computation.
double get_average() const
Returns the average orientation (radians).
void append(const mrpt::math::CMatrixDouble33 &M, const double weight)
Adds a new orientation to the weighted-average computation.
void append(const mrpt::math::TPose2D &p, const double weight)
void clear()
Resets the accumulator.
void get_average(mrpt::poses::CPose3D &out_mean) const
Returns the average pose.
void clear()
Resets the accumulator.
void append(const mrpt::poses::CPose3D &p, const double weight)
Adds a new pose to the weighted-average computation.
void clear()
Resets the accumulator.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void append(const double orientation_rad)
Adds a new orientation (radians) to the computation.
void clear()
Resets the accumulator.
void get_average(mrpt::poses::CPose2D &out_mean) const
Returns the average pose.
Computes weighted and un-weighted averages of SO(2) orientations.
mrpt::math::CMatrixDouble33 get_average() const
Returns the average orientation.
SO_average< 2 > m_rot_part
void append(const mrpt::poses::CPose3D &p)
Adds a new pose to the computation.
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).
void append(const mrpt::math::CMatrixDouble33 &M)
Adds a new orientation to the computation.
void append(const mrpt::math::TPose3D &p, const double weight)
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.
void append(const mrpt::poses::CPose2D &p)
Adds a new pose to the computation.
Page generated by Doxygen 1.8.18 for MRPT 2.0.4 at Thu Sep 24 07:14:18 UTC 2020 | |