9#ifndef MRPT_SE2_SE3_AVERAGE_H
10#define MRPT_SE2_SE3_AVERAGE_H
43 void append(
const double orientation_rad);
44 void append(
const double orientation_rad,
const double weight);
69 void append(
const Eigen::Matrix3d &M);
70 void append(
const Eigen::Matrix3d &M,
const double weight);
A class used to store a 2D pose.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void clear()
Resets the accumulator.
void append(const mrpt::poses::CPose2D &p, const double weight)
Adds a new pose to the weighted-average computation.
void append(const mrpt::poses::CPose2D &p)
Adds a new pose to the computation.
SO_average< 2 > m_rot_part
void get_average(mrpt::poses::CPose2D &out_mean) const
Returns the average pose.
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
SO_average< 3 > m_rot_part
void get_average(mrpt::poses::CPose3D &out_mean) const
Returns the average pose.
void clear()
Resets the accumulator.
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
void append(const mrpt::poses::CPose3D &p)
Adds a new pose to the computation.
void append(const mrpt::poses::CPose3D &p, const double weight)
Adds a new pose to the weighted-average computation.
Computes weighted and un-weighted averages of SO(2) orientations.
void clear()
Resets the accumulator.
void append(const double orientation_rad, const double weight)
Adds a new orientation (radians) to the weighted-average computation.
void append(const double orientation_rad)
Adds a new orientation (radians) to the computation.
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
double get_average() const
Returns the average orientation (radians).
Computes weighted and un-weighted averages of SO(3) orientations.
void append(const Eigen::Matrix3d &M, const double weight)
Adds a new orientation to the weighted-average computation.
Eigen::Matrix3d m_accum_rot
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
void append(const Eigen::Matrix3d &M)
Adds a new orientation to the computation.
Eigen::Matrix3d get_average() const
Returns the average orientation.
void clear()
Resets the accumulator.
class BASE_IMPEXP SO_average
Computes weighted and un-weighted averages of SO(2) or SO(3) orientations.
class BASE_IMPEXP SE_average
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.