Go to the documentation of this file.
9 #ifndef MRPT_SE2_SE3_AVERAGE_H
10 #define MRPT_SE2_SE3_AVERAGE_H
52 void append(
const double orientation_rad);
55 void append(
const double orientation_rad,
const double weight);
63 double get_average()
const;
94 void append(
const Eigen::Matrix3d& M);
97 void append(
const Eigen::Matrix3d& M,
const double weight);
104 Eigen::Matrix3d get_average()
const;
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
void clear()
Clear the contents of this container.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
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).
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
bool enable_exception_on_undeterminate
(Default=false) Set to true if you want to raise an exception on undetermined average values.
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
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
Computes weighted and un-weighted averages of SO(3) orientations.
Eigen::Matrix3d m_accum_rot
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |