Main MRPT website > C++ reference for MRPT 1.9.9
SO_SE_average.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "base-precomp.h" // Precompiled headers
11 
13 
14 using namespace mrpt;
15 using namespace mrpt::math;
16 using namespace mrpt::utils;
17 using namespace mrpt::poses;
18 
19 // ----------- SO_average<2> --------------------
21  : enable_exception_on_undeterminate(false),
22  m_count(0),
23  m_accum_x(0),
24  m_accum_y(0)
25 {
26 }
28 {
29  m_count = .0;
30  m_accum_x = m_accum_y = .0;
31 }
32 void SO_average<2>::append(const double orientation_rad)
33 {
34  append(orientation_rad, 1.0);
35 }
36 void SO_average<2>::append(const double orientation_rad, const double weight)
37 {
38  m_count += weight;
39  m_accum_x += cos(orientation_rad) * weight;
40  m_accum_y += sin(orientation_rad) * weight;
41 }
42 double SO_average<2>::get_average() const
43 {
44  ASSERT_ABOVE_(m_count, 0);
45  const double x = m_accum_x / m_count;
46  const double y = m_accum_y / m_count;
47  errno = 0;
48  double ang = atan2(y, x);
49  if (errno == EDOM)
50  {
51  if (enable_exception_on_undeterminate)
52  throw std::runtime_error(
53  "[SO_average<2>::get_average()] Undetermined average value");
54  else
55  ang = 0;
56  }
57  return ang;
58 }
59 
60 // ----------- SO_average<3> --------------------
62  : enable_exception_on_undeterminate(false), m_count(0), m_accum_rot()
63 {
64  clear();
65 }
67 {
68  m_count = .0;
69  m_accum_rot.setZero();
70 }
71 void SO_average<3>::append(const Eigen::Matrix3d& M) { append(M, 1.0); }
72 void SO_average<3>::append(const Eigen::Matrix3d& M, const double weight)
73 {
74  m_count += weight;
75  m_accum_rot += weight * M;
76 }
77 // See: eq. (3.7) in "MEANS AND AVERAGING IN THE GROUP OF ROTATIONS", MAHER
78 // MOAKHER, 2002.
79 Eigen::Matrix3d SO_average<3>::get_average() const
80 {
81  ASSERT_ABOVE_(m_count, 0);
82  const Eigen::Matrix3d MtM = m_accum_rot.transpose() * m_accum_rot;
83 
84  Eigen::JacobiSVD<Eigen::Matrix3d> svd(MtM, Eigen::ComputeFullU);
85  const Eigen::Vector3d vs = svd.singularValues();
86 
87  errno = 0;
88  const double d1 = 1.0 / sqrt(vs[0]);
89  const double d2 = 1.0 / sqrt(vs[1]);
90  const double d3 =
91  mrpt::utils::sign(m_accum_rot.determinant()) / sqrt(vs[2]);
92  if (errno != 0)
93  {
94  if (enable_exception_on_undeterminate)
95  throw std::runtime_error(
96  "[SO_average<3>::get_average()] Undetermined average value");
97  else
98  return Eigen::Matrix3d::Identity();
99  }
100 
101  Eigen::Matrix3d D = Eigen::Matrix3d::Zero();
102  D(0, 0) = d1;
103  D(1, 1) = d2;
104  D(2, 2) = d3;
105  Eigen::Matrix3d ret =
106  m_accum_rot * svd.matrixU() * D * svd.matrixU().transpose();
107  return ret;
108 }
109 
110 // ----------- SE_average<2> --------------------
112  : enable_exception_on_undeterminate(false),
113  m_count(0),
114  m_accum_x(0),
115  m_accum_y(0),
116  m_rot_part()
117 {
118  clear();
119 }
121 {
122  m_count = .0;
123  m_accum_x = m_accum_y = .0;
124  m_rot_part.clear();
125 }
126 void SE_average<2>::append(const mrpt::poses::CPose2D& p) { append(p, 1.0); }
127 void SE_average<2>::append(const mrpt::poses::CPose2D& p, const double weight)
128 {
129  m_count += weight;
130  m_accum_x += weight * p.x();
131  m_accum_y += weight * p.y();
132  m_rot_part.append(p.phi(), weight);
133 }
135 {
136  ASSERT_ABOVE_(m_count, 0);
137  ret_mean.x(m_accum_x / m_count);
138  ret_mean.y(m_accum_y / m_count);
139  const_cast<SO_average<2>*>(&m_rot_part)->enable_exception_on_undeterminate =
140  this->enable_exception_on_undeterminate;
141  ret_mean.phi(m_rot_part.get_average());
142 }
143 
144 // ----------- SE_average<3> --------------------
146  : enable_exception_on_undeterminate(false),
147  m_count(0),
148  m_accum_x(0),
149  m_accum_y(0),
150  m_accum_z(0),
151  m_rot_part()
152 {
153  clear();
154 }
156 {
157  m_count = .0;
158  m_accum_x = m_accum_y = m_accum_z = .0;
159  m_rot_part.clear();
160 }
161 void SE_average<3>::append(const mrpt::poses::CPose3D& p) { append(p, 1.0); }
162 void SE_average<3>::append(const mrpt::poses::CPose3D& p, const double weight)
163 {
164  m_count += weight;
165  m_accum_x += weight * p.x();
166  m_accum_y += weight * p.y();
167  m_accum_z += weight * p.z();
168  m_rot_part.append(p.getRotationMatrix(), weight);
169 }
171 {
172  ASSERT_ABOVE_(m_count, 0);
173  ret_mean.x(m_accum_x / m_count);
174  ret_mean.y(m_accum_y / m_count);
175  ret_mean.z(m_accum_z / m_count);
176  const_cast<SO_average<3>*>(&m_rot_part)->enable_exception_on_undeterminate =
177  this->enable_exception_on_undeterminate;
178  ret_mean.setRotationMatrix(m_rot_part.get_average());
179 }
double x() const
Common members of all points & poses classes.
Definition: CPoseOrPoint.h:135
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Computes weighted and un-weighted averages of SO(2) orientations.
Definition: SO_SE_average.h:44
#define ASSERT_ABOVE_(__A, __B)
Computes weighted and un-weighted averages of SE(2) or SE(3) poses.
Definition: SO_SE_average.h:31
int sign(T x)
Returns the sign of X as "1" or "-1".
void clear()
Clear the contents of this container.
Definition: ts_hash_map.h:189
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
Sets the 3x3 rotation matrix.
Definition: CPose3D.h:249
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
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:40
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
const double & phi() const
Get the phi angle of the 2D pose (in radians)
Definition: CPose2D.h:91
Computes weighted and un-weighted averages of SO(3) orientations.
Definition: SO_SE_average.h:86
Computes weighted and un-weighted averages of SO(2) or SO(3) orientations.
Definition: SO_SE_average.h:26
GLenum GLint GLint y
Definition: glext.h:3538
GLenum GLint x
Definition: glext.h:3538
GLfloat GLfloat p
Definition: glext.h:6305



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019