MRPT  1.9.9
SO_SE_average.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2019, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "poses-precomp.h" // Precompiled headers
11 
12 #include <mrpt/math/TPose2D.h>
13 #include <mrpt/math/TPose3D.h>
15 #include <Eigen/Dense>
16 
17 using namespace mrpt;
18 using namespace mrpt::math;
19 
20 using namespace mrpt::poses;
21 
22 // ----------- SO_average<2> --------------------
23 SO_average<2>::SO_average() = default;
24 
26 {
27  m_count = .0;
28  m_accum_x = m_accum_y = .0;
29 }
30 void SO_average<2>::append(const double orientation_rad)
31 {
32  append(orientation_rad, 1.0);
33 }
34 void SO_average<2>::append(const double orientation_rad, const double weight)
35 {
36  m_count += weight;
37  m_accum_x += cos(orientation_rad) * weight;
38  m_accum_y += sin(orientation_rad) * weight;
39 }
40 double SO_average<2>::get_average() const
41 {
42  ASSERT_ABOVE_(m_count, 0);
43  const double x = m_accum_x / m_count;
44  const double y = m_accum_y / m_count;
45  errno = 0;
46  double ang = atan2(y, x);
47  if (errno == EDOM)
48  {
49  if (enable_exception_on_undeterminate)
50  throw std::runtime_error(
51  "[SO_average<2>::get_average()] Undetermined average value");
52  else
53  ang = 0;
54  }
55  return ang;
56 }
57 
58 // ----------- SO_average<3> --------------------
59 SO_average<3>::SO_average() : m_accum_rot() { clear(); }
61 {
62  m_count = .0;
63  m_accum_rot.setZero();
64 }
66 {
67  append(M, 1.0);
68 }
70  const mrpt::math::CMatrixDouble33& M, const double weight)
71 {
72  m_count += weight;
73  m_accum_rot.asEigen() += weight * M.asEigen();
74 }
75 // See: eq. (3.7) in "MEANS AND AVERAGING IN THE GROUP OF ROTATIONS", MAHER
76 // MOAKHER, 2002.
78 {
79  ASSERT_ABOVE_(m_count, 0);
80  const Eigen::Matrix3d MtM = m_accum_rot.transpose() * m_accum_rot.asEigen();
81 
82  Eigen::JacobiSVD<Eigen::Matrix3d> svd(MtM, Eigen::ComputeFullU);
83  const Eigen::Vector3d vs = svd.singularValues();
84 
85  errno = 0;
86  const double d1 = 1.0 / sqrt(vs[0]);
87  const double d2 = 1.0 / sqrt(vs[1]);
88  const double d3 = mrpt::sign(m_accum_rot.det()) / sqrt(vs[2]);
89  if (errno != 0)
90  {
91  if (enable_exception_on_undeterminate)
92  throw std::runtime_error(
93  "[SO_average<3>::get_average()] Undetermined average value");
94  else
96  }
97 
99  D(0, 0) = d1;
100  D(1, 1) = d2;
101  D(2, 2) = d3;
103  m_accum_rot.asEigen() * svd.matrixU() * D.asEigen() *
104  svd.matrixU().transpose());
105 }
106 
107 // ----------- SE_average<2> --------------------
108 SE_average<2>::SE_average() : m_rot_part() { clear(); }
110 {
111  m_count = .0;
112  m_accum_x = m_accum_y = .0;
113  m_rot_part.clear();
114 }
115 void SE_average<2>::append(const mrpt::poses::CPose2D& p) { append(p, 1.0); }
116 void SE_average<2>::append(const mrpt::poses::CPose2D& p, const double weight)
117 {
118  m_count += weight;
119  m_accum_x += weight * p.x();
120  m_accum_y += weight * p.y();
121  m_rot_part.append(p.phi(), weight);
122 }
123 void SE_average<2>::append(const mrpt::math::TPose2D& p, const double weight)
124 {
125  m_count += weight;
126  m_accum_x += weight * p.x;
127  m_accum_y += weight * p.y;
128  m_rot_part.append(p.phi, weight);
129 }
131 {
132  ASSERT_ABOVE_(m_count, 0);
133  ret_mean.x(m_accum_x / m_count);
134  ret_mean.y(m_accum_y / m_count);
135  const_cast<SO_average<2>*>(&m_rot_part)->enable_exception_on_undeterminate =
136  this->enable_exception_on_undeterminate;
137  ret_mean.phi(m_rot_part.get_average());
138 }
139 
140 // ----------- SE_average<3> --------------------
141 SE_average<3>::SE_average() : m_rot_part() { clear(); }
143 {
144  m_count = .0;
145  m_accum_x = m_accum_y = m_accum_z = .0;
146  m_rot_part.clear();
147 }
148 void SE_average<3>::append(const mrpt::poses::CPose3D& p) { append(p, 1.0); }
149 void SE_average<3>::append(const mrpt::poses::CPose3D& p, const double weight)
150 {
151  m_count += weight;
152  m_accum_x += weight * p.x();
153  m_accum_y += weight * p.y();
154  m_accum_z += weight * p.z();
155  m_rot_part.append(p.getRotationMatrix(), weight);
156 }
157 void SE_average<3>::append(const mrpt::math::TPose3D& p, const double weight)
158 {
159  append(CPose3D(p), weight);
160 }
162 {
163  ASSERT_ABOVE_(m_count, 0);
164  ret_mean.x(m_accum_x / m_count);
165  ret_mean.y(m_accum_y / m_count);
166  ret_mean.z(m_accum_z / m_count);
167  const_cast<SO_average<3>*>(&m_rot_part)->enable_exception_on_undeterminate =
168  this->enable_exception_on_undeterminate;
169  ret_mean.setRotationMatrix(m_rot_part.get_average());
170 }
Computes weighted and un-weighted averages of SO(2) orientations.
Definition: SO_SE_average.h:41
static Derived Identity()
Definition: MatrixBase.h:64
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
Definition: SO_SE_average.h:28
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
Sets the 3x3 rotation matrix.
Definition: CPose3D.h:236
CMatrixFixed< double, 3, 3 > CMatrixDouble33
Definition: CMatrixFixed.h:352
This base provides a set of functions for maths stuff.
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:143
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:84
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:86
#define ASSERT_ABOVE_(__A, __B)
Definition: exceptions.h:155
Computes weighted and un-weighted averages of SO(3) orientations.
Definition: SO_SE_average.h:83
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Definition: TPose3D.h:23
Lightweight 2D pose.
Definition: TPose2D.h:22
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
Definition: CMatrixFixed.h:251
Computes weighted and un-weighted averages of SO(2) or SO(3) orientations.
Definition: SO_SE_average.h:23
GLenum GLint GLint y
Definition: glext.h:3542
int sign(T x)
Returns the sign of X as "1" or "-1".
GLenum GLint x
Definition: glext.h:3542
GLfloat GLfloat p
Definition: glext.h:6398
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:182



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 8fe78517f Sun Jul 14 19:43:28 2019 +0200 at lun oct 28 02:10:00 CET 2019