treeoptimizer3.cpp
Go to the documentation of this file.
1 /**********************************************************************
2  *
3  * This source code is part of the Tree-based Network Optimizer (TORO)
4  *
5  * TORO Copyright (c) 2007 Giorgio Grisetti, Cyrill Stachniss,
6  * Slawomir Grzonka, and Wolfram Burgard
7  *
8  * TORO is licences under the Common Creative License,
9  * Attribution-NonCommercial-ShareAlike 3.0
10  *
11  * You are free:
12  * - to Share - to copy, distribute and transmit the work
13  * - to Remix - to adapt the work
14  *
15  * Under the following conditions:
16  *
17  * - Attribution. You must attribute the work in the manner specified
18  * by the author or licensor (but not in any way that suggests that
19  * they endorse you or your use of the work).
20  *
21  * - Noncommercial. You may not use this work for commercial purposes.
22  *
23  * - Share Alike. If you alter, transform, or build upon this work,
24  * you may distribute the resulting work only under the same or
25  * similar license to this one.
26  *
27  * Any of the above conditions can be waived if you get permission
28  * from the copyright holder. Nothing in this license impairs or
29  * restricts the author's moral rights.
30  *
31  * TORO is distributed in the hope that it will be useful,
32  * but WITHOUT ANY WARRANTY; without even the implied
33  * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
34  * PURPOSE.
35  **********************************************************************/
36 
44 #include "treeoptimizer3.h"
45 
46 #include <fstream>
47 #include <sstream>
48 #include <string>
49 
50 using namespace std;
51 
52 namespace AISNavigation {
53 
54 //#define DEBUG(i) if (verboseLevel>i) cerr
55 
56 
57 TreeOptimizer3::TreeOptimizer3(){
58  restartOnDivergence=false;
59  sortedEdges=0;
60  mpl=-1;
61  edgeCompareMode=EVComparator<Edge*>::CompareLevel;
62 }
63 
64 
65 TreeOptimizer3::~TreeOptimizer3(){
66 }
67 
68 void TreeOptimizer3::initializeTreeParameters(){
70  treeDepthVisit(pp,root);
71 }
72 
73 
74 void TreeOptimizer3::iterate(TreePoseGraph3::EdgeSet* eset, bool noPreconditioner){
75  TreePoseGraph3::EdgeSet* temp=sortedEdges;
76  if (eset){
77  sortedEdges=eset;
78  }
79 
80  if (noPreconditioner)
81  propagateErrors(false);
82  else {
83  if (iteration==1)
84  computePreconditioner();
85  propagateErrors(true);
86  }
87  sortedEdges=temp;
88 
89  onRestartBegin();
90  if (restartOnDivergence){
91  double mte, ate;
92  double mre, are;
93  error(&mre, &mte, &are, &ate);
94  maxTranslationalErrors.push_back(mte);
95  maxRotationalErrors.push_back(mre);
96  int interval=3;
97  if ((int)maxRotationalErrors.size()>=interval){
98  uint s=(uint)maxRotationalErrors.size();
99  double re0 = maxRotationalErrors[s-interval];
100  double re1 = maxRotationalErrors[s-1];
101 
102  if ((re1-re0)>are || sqrt(re1)>0.99*M_PI){
103  double rg=rotGain;
104  if (sqrt(re1)>M_PI/4){
105  cerr << "RESTART!!!!! : Angular wraparound may be occourring" << endl;
106  cerr << " err=" << re0 << " -> " << re1 << endl;
107  cerr << "Restarting optimization and reducing the rotation factor" << endl;
108  cerr << rg << " -> ";
109  initializeOnTree();
110  initializeTreeParameters();
111  initializeOptimization();
112  error(&mre, &mte);
113  maxTranslationalErrors.push_back(mte);
114  maxRotationalErrors.push_back(mre);
115  rg*=0.1;
116  rotGain=rg;
117  cerr << rotGain << endl;
118  }
119  else {
120  cerr << "decreasing angular gain" << rotGain*0.1 << endl;
121  rotGain*=0.1;
122  }
123  }
124  }
125  }
126  onRestartDone();
127 }
128 
129 
130 void TreeOptimizer3::recomputeTransformations(Vertex*v, Vertex* top){
131  if (v==top)
132  return;
133  recomputeTransformations(v->parent, top);
134  v->transformation=v->parent->transformation*v->parameters;
135 }
136 
137 
138 void TreeOptimizer3::recomputeParameters(Vertex*v, Vertex* top){
139  while (v!=top){
140  v->parameters=v->parent->transformation.inv()*v->transformation;
141  v=v->parent;
142  }
143 }
144 
145 
146 TreeOptimizer3::Transformation TreeOptimizer3::getPose(Vertex*v, Vertex* top){
147  Transformation t(0.,0.,0.,0.,0.,0.);
148  if (v==top)
149  return v->transformation;
150  while (v!=top){
151  t=v->parameters*t;
152  v=v->parent;
153  }
154  return top->transformation*t;
155 }
156 
157 TreeOptimizer3::Rotation TreeOptimizer3::getRotation(Vertex*v, Vertex* top){
158  Rotation r(0.,0.,0.);
159  if (v==top)
160  return v->transformation.rotation();
161  while (v!=top){
162  r=v->parameters.rotation()*r;
163  v=v->parent;
164  }
165  return top->transformation.rotation()*r;
166 }
167 
168 
169 
170 double TreeOptimizer3::error(const Edge* e) const{
171  const Vertex* v1=e->v1;
172  const Vertex* v2=e->v2;
173 
174  Transformation et=e->transformation;
175  Transformation t1=v1->transformation;
176  Transformation t2=v2->transformation;
177 
178  Transformation t12=(t1*et)*t2.inv();
179  Pose p12=t12.toPoseType();
180 
181  Pose ps=e->informationMatrix*p12;
182  double err=p12*ps;
183  //DEBUG(100) << "e(" << v1->id << "," << v2->id << ")" << err << endl;
184  return err;
185 
186 }
187 
188 double TreeOptimizer3::traslationalError(const Edge* e) const{
189  const Vertex* v1=e->v1;
190  const Vertex* v2=e->v2;
191 
192  Transformation et=e->transformation;
193  Transformation t1=v1->transformation;
194  Transformation t2=v2->transformation;
195 
196  Translation t12=(t2.inv()*(t1*et)).translation();
197  return t12*t12;;
198 
199 }
200 
201 double TreeOptimizer3::rotationalError(const Edge* e) const{
202  const Vertex* v1=e->v1;
203  const Vertex* v2=e->v2;
204 
205  Rotation er=e->transformation.rotation();
206  Rotation r1=v1->transformation.rotation();
207  Rotation r2=v2->transformation.rotation();
208 
209  Rotation r12=r2.inverse()*(r1*er);
210  double r=r12.angle();
211  return r*r;
212 }
213 
214 
215 double TreeOptimizer3::loopError(const Edge* e) const{
216  double err=0;
217  const Vertex* v=e->v1;
218  while (v!=e->top){
219  err+=error(v->parentEdge);
220  v=v->parent;
221  }
222  v=e->v2;
223  while (v==e->top){
224  err+=error(v->parentEdge);
225  v=v->parent;
226  }
227  if (e->v2->parentEdge!=e && e->v1->parentEdge!=e)
228  err+=error(e);
229  return err;
230 }
231 
232 double TreeOptimizer3::loopRotationalError(const Edge* e) const{
233  double err=0;
234  const Vertex* v=e->v1;
235  while (v!=e->top){
236  err+=rotationalError(v->parentEdge);
237  v=v->parent;
238  }
239  v=e->v2;
240  while (v!=e->top){
241  err+=rotationalError(v->parentEdge);
242  v=v->parent;
243  }
244  if (e->v2->parentEdge!=e && e->v1->parentEdge!=e)
245  err+=rotationalError(e);
246  return err;
247 }
248 
249 
250 double TreeOptimizer3::error(double* mre, double* mte, double* are, double* ate, TreePoseGraph3::EdgeSet* eset) const{
251  double globalRotError=0.;
252  double maxRotError=0;
253  double globalTrasError=0.;
254  double maxTrasError=0;
255 
256  int c=0;
257  if (! eset){
258  for (TreePoseGraph3::EdgeMap::const_iterator it=edges.begin(); it!=edges.end(); it++){
259  double re=rotationalError(it->second);
260  globalRotError+=re;
261  maxRotError=maxRotError>re?maxRotError:re;
262  double te=traslationalError(it->second);
263  globalTrasError+=te;
264  maxTrasError=maxTrasError>te?maxTrasError:te;
265  c++;
266  }
267  } else {
268  for (TreePoseGraph3::EdgeSet::const_iterator it=eset->begin(); it!=eset->end(); it++){
269  const TreePoseGraph3::Edge* edge=*it;
270  double re=rotationalError(edge);
271  globalRotError+=re;
272  maxRotError=maxRotError>re?maxRotError:re;
273  double te=traslationalError(edge);
274  globalTrasError+=te;
275  maxTrasError=maxTrasError>te?maxTrasError:te;
276  c++;
277  }
278  }
279 
280  if (mte)
281  *mte=maxTrasError;
282  if (mre)
283  *mre=maxRotError;
284  if (ate)
285  *ate=globalTrasError/c;
286  if (are)
287  *are=globalRotError/c;
288  return globalRotError+globalTrasError;
289 }
290 
291 
292 
293 void TreeOptimizer3::initializeOptimization(EdgeCompareMode mode){
294  edgeCompareMode=mode;
295  // compute the size of the preconditioning matrix
296  int sz=maxIndex()+1;
297  //DEBUG(1) << "Size= " << sz << endl;
298  M.resize(sz);
299 
300  //DEBUG(1) << "allocating M(" << sz << ")" << endl;
301  iteration=1;
302 
303  // sorting edges
304  if (sortedEdges!=0){
305  delete sortedEdges;
306  sortedEdges=0;
307  }
308  sortedEdges=sortEdges();
309  mpl=maxPathLength();
310  rotGain=1.;
311  trasGain=1.;
312 }
313 
314 void TreeOptimizer3::initializeOnlineIterations(){
315  int sz=maxIndex()+1;
316  //DEBUG(1) << "Size= " << sz << endl;
317  M.resize(sz);
318  //DEBUG(1) << "allocating M(" << sz << ")" << endl;
319  iteration=1;
320  maxRotationalErrors.clear();
321  maxTranslationalErrors.clear();
322  rotGain=1.;
323  trasGain=1.;
324 }
325 
326 void TreeOptimizer3::initializeOnlineOptimization(EdgeCompareMode mode){
327  edgeCompareMode=mode;
328  // compute the size of the preconditioning matrix
329  clear();
330  Vertex* v0=addVertex(0,Pose(0,0,0,0,0,0));
331  root=v0;
332  v0->parameters=Transformation(v0->pose);
333  v0->parentEdge=0;
334  v0->parent=0;
335  v0->level=0;
336  v0->transformation=Transformation(TreePoseGraph3::Pose(0,0,0,0,0,0));
337 }
338 
339 void TreeOptimizer3::onStepStart(Edge* e){
340  //DEBUG(5) << "entering edge" << e << endl;
341 }
342 void TreeOptimizer3::onStepFinished(Edge* e){
343  //DEBUG(5) << "exiting edge" << e << endl;
344 }
345 
346 void TreeOptimizer3::onIterationStart(int iteration){
347  //DEBUG(5) << "entering iteration " << iteration << endl;
348 }
349 
350 void TreeOptimizer3::onIterationFinished(int iteration){
351  //DEBUG(5) << "exiting iteration " << iteration << endl;
352 }
353 
354 void TreeOptimizer3::onRestartBegin(){}
355 void TreeOptimizer3::onRestartDone(){}
356 bool TreeOptimizer3::isDone(){
357  return false;
358 }
359 
360 
361 }; //namespace AISNavigation
v1
v1
s
RealScalar s
c
Scalar Scalar * c
edges
vector< MFAS::KeyPair > edges
AISNavigation::Transformation3::inv
Transformation3< T > inv() const
AISNavigation::Quaternion::inverse
Quaternion< T > inverse() const
Eigen::PlainObjectBase::resize
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
AISNavigation::Transformation3::toPoseType
Pose3< T > toPoseType() const
AISNavigation::TreePoseGraph3::ParameterPropagator
A class (struct) to compute the parameterization of the vertex v.
Definition: posegraph3.h:118
AISNavigation::Pose3
Definition: transformation3.h:108
mode
const DiscreteKey mode
AISNavigation::Quaternion::angle
T angle() const
glm::sqrt
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
AISNavigation::uint
unsigned int uint
Definition: posegraph2.cpp:54
error
void error(const char *str)
M_PI
#define M_PI
Definition: tango-gl/include/tango-gl/util.h:66
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
AISNavigation::Vector3
Definition: transformation3.h:82
AISNavigation::Quaternion
Definition: transformation3.h:140
treeoptimizer3.h
std
glm::uint
unsigned int uint
Definition: type_int.hpp:170
v
Array< int, Dynamic, 1 > v
ps
int RealScalar int RealScalar int RealScalar RealScalar * ps
AISNavigation::EVComparator
A comparator class (struct) that compares the level of two vertices if edges.
Definition: posegraph.h:62
Eigen.Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor >
root
root
t
Point2 t(10, 10)
AISNavigation
Definition: posegraph.h:57
v2
v2
AISNavigation::Transformation3
Definition: transformation3.h:256


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:22