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-2020, 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 using namespace mrpt::poses;
20 
21 // ----------- SO_average<2> --------------------
22 SO_average<2>::SO_average() = default;
23 
25 {
26  m_count = .0;
27  m_accum_x = m_accum_y = .0;
28 }
29 void SO_average<2>::append(const double orientation_rad)
30 {
31  append(orientation_rad, 1.0);
32 }
33 void SO_average<2>::append(const double orientation_rad, const double weight)
34 {
35  m_count += weight;
36  m_accum_x += cos(orientation_rad) * weight;
37  m_accum_y += sin(orientation_rad) * weight;
38 }
39 double SO_average<2>::get_average() const
40 {
41  ASSERT_ABOVE_(m_count, 0);
42  const double x = m_accum_x / m_count;
43  const double y = m_accum_y / m_count;
44  errno = 0;
45  double ang = atan2(y, x);
46  if (errno == EDOM)
47  {
48  if (enable_exception_on_undeterminate)
49  throw std::runtime_error(
50  "[SO_average<2>::get_average()] Undetermined average value");
51  else
52  ang = 0;
53  }
54  return ang;
55 }
56 
57 // ----------- SO_average<3> --------------------
58 SO_average<3>::SO_average() : m_accum_rot() { clear(); }
60 {
61  m_count = .0;
62  m_accum_rot.setZero();
63 }
65 {
66  append(M, 1.0);
67 }
69  const mrpt::math::CMatrixDouble33& M, const double weight)
70 {
71  m_count += weight;
72  m_accum_rot.asEigen() += weight * M.asEigen();
73 }
74 // See: eq. (3.7) in "MEANS AND AVERAGING IN THE GROUP OF ROTATIONS", MAHER
75 // MOAKHER, 2002.
77 {
78  ASSERT_ABOVE_(m_count, 0);
79  const Eigen::Matrix3d MtM = m_accum_rot.transpose() * m_accum_rot.asEigen();
80 
81  Eigen::JacobiSVD<Eigen::Matrix3d> svd(MtM, Eigen::ComputeFullU);
82  const Eigen::Vector3d vs = svd.singularValues();
83 
84  errno = 0;
85  const double d1 = 1.0 / sqrt(vs[0]);
86  const double d2 = 1.0 / sqrt(vs[1]);
87  const double d3 = mrpt::sign(m_accum_rot.det()) / sqrt(vs[2]);
88  if (errno != 0)
89  {
90  if (enable_exception_on_undeterminate)
91  throw std::runtime_error(
92  "[SO_average<3>::get_average()] Undetermined average value");
93  else
95  }
96 
98  D(0, 0) = d1;
99  D(1, 1) = d2;
100  D(2, 2) = d3;
102  m_accum_rot.asEigen() * svd.matrixU() * D.asEigen() *
103  svd.matrixU().transpose());
104 }
105 
106 // ----------- SE_average<2> --------------------
107 SE_average<2>::SE_average() : m_rot_part() { clear(); }
109 {
110  m_count = .0;
111  m_accum_x = m_accum_y = .0;
112  m_rot_part.clear();
113 }
114 void SE_average<2>::append(const mrpt::poses::CPose2D& p) { append(p, 1.0); }
115 void SE_average<2>::append(const mrpt::poses::CPose2D& p, const double weight)
116 {
117  m_count += weight;
118  m_accum_x += weight * p.x();
119  m_accum_y += weight * p.y();
120  m_rot_part.append(p.phi(), weight);
121 }
122 void SE_average<2>::append(const mrpt::math::TPose2D& p, const double weight)
123 {
124  m_count += weight;
125  m_accum_x += weight * p.x;
126  m_accum_y += weight * p.y;
127  m_rot_part.append(p.phi, weight);
128 }
130 {
131  ASSERT_ABOVE_(m_count, 0);
132  ret_mean.x(m_accum_x / m_count);
133  ret_mean.y(m_accum_y / m_count);
134  const_cast<SO_average<2>*>(&m_rot_part)->enable_exception_on_undeterminate =
135  this->enable_exception_on_undeterminate;
136  ret_mean.phi(m_rot_part.get_average());
137 }
138 
139 // ----------- SE_average<3> --------------------
140 SE_average<3>::SE_average() : m_rot_part() { clear(); }
142 {
143  m_count = .0;
144  m_accum_x = m_accum_y = m_accum_z = .0;
145  m_rot_part.clear();
146 }
147 void SE_average<3>::append(const mrpt::poses::CPose3D& p) { append(p, 1.0); }
148 void SE_average<3>::append(const mrpt::poses::CPose3D& p, const double weight)
149 {
150  m_count += weight;
151  m_accum_x += weight * p.x();
152  m_accum_y += weight * p.y();
153  m_accum_z += weight * p.z();
154  m_rot_part.append(p.getRotationMatrix(), weight);
155 }
156 void SE_average<3>::append(const mrpt::math::TPose3D& p, const double weight)
157 {
158  append(CPose3D(p), weight);
159 }
161 {
162  ASSERT_ABOVE_(m_count, 0);
163  ret_mean.x(m_accum_x / m_count);
164  ret_mean.y(m_accum_y / m_count);
165  ret_mean.z(m_accum_z / m_count);
166  const_cast<SO_average<3>*>(&m_rot_part)->enable_exception_on_undeterminate =
167  this->enable_exception_on_undeterminate;
168  ret_mean.setRotationMatrix(m_rot_part.get_average());
169 }
Computes weighted and un-weighted averages of SO(2) orientations.
Definition: SO_SE_average.h:41
static Derived Identity()
Definition: MatrixBase.h:64
double x
X,Y coordinates.
Definition: TPose2D.h:30
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:237
CMatrixFixed< double, 3, 3 > CMatrixDouble33
Definition: CMatrixFixed.h:367
This base provides a set of functions for maths stuff.
double phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:86
int sign(T x)
Returns the sign of X as "1" or "-1".
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:85
#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:24
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
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
Definition: CPose3D.h:225
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:183
double phi
Orientation (rads)
Definition: TPose2D.h:32



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020