Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00044 #include "treeoptimizer3.hh"
00045 #include <fstream>
00046 #include <sstream>
00047 #include <string>
00048
00049 using namespace std;
00050
00051 namespace AISNavigation {
00052
00053 #define DEBUG(i) \
00054 if (verboseLevel>i) cerr
00055
00056
00057 TreeOptimizer3::TreeOptimizer3(){
00058 restartOnDivergence=false;
00059 sortedEdges=0;
00060 mpl=-1;
00061 edgeCompareMode=EVComparator<Edge*>::CompareLevel;
00062 }
00063
00064
00065 TreeOptimizer3::~TreeOptimizer3(){
00066 }
00067
00068 void TreeOptimizer3::initializeTreeParameters(){
00069 ParameterPropagator pp;
00070 treeDepthVisit(pp,root);
00071 }
00072
00073
00074 void TreeOptimizer3::iterate(TreePoseGraph3::EdgeSet* eset, bool noPreconditioner){
00075 TreePoseGraph3::EdgeSet* temp=sortedEdges;
00076 if (eset){
00077 sortedEdges=eset;
00078 }
00079
00080 if (noPreconditioner)
00081 propagateErrors(false);
00082 else {
00083 if (iteration==1)
00084 computePreconditioner();
00085 propagateErrors(true);
00086 }
00087 sortedEdges=temp;
00088
00089 onRestartBegin();
00090 if (restartOnDivergence){
00091 double mte, ate;
00092 double mre, are;
00093 error(&mre, &mte, &are, &ate);
00094 maxTranslationalErrors.push_back(mte);
00095 maxRotationalErrors.push_back(mre);
00096 int interval=3;
00097 if ((int)maxRotationalErrors.size()>=interval){
00098 uint s=(uint)maxRotationalErrors.size();
00099 double re0 = maxRotationalErrors[s-interval];
00100 double re1 = maxRotationalErrors[s-1];
00101
00102 if ((re1-re0)>are || sqrt(re1)>0.99*M_PI){
00103 double rg=rotGain;
00104 if (sqrt(re1)>M_PI/4){
00105 cerr << "RESTART!!!!! : Angular wraparound may be occourring" << endl;
00106 cerr << " err=" << re0 << " -> " << re1 << endl;
00107 cerr << "Restarting optimization and reducing the rotation factor" << endl;
00108 cerr << rg << " -> ";
00109 initializeOnTree();
00110 initializeTreeParameters();
00111 initializeOptimization();
00112 error(&mre, &mte);
00113 maxTranslationalErrors.push_back(mte);
00114 maxRotationalErrors.push_back(mre);
00115 rg*=0.1;
00116 rotGain=rg;
00117 cerr << rotGain << endl;
00118 }
00119 else {
00120 cerr << "decreasing angular gain" << rotGain*0.1 << endl;
00121 rotGain*=0.1;
00122 }
00123 }
00124 }
00125 }
00126 onRestartDone();
00127 }
00128
00129
00130 void TreeOptimizer3::recomputeTransformations(Vertex*v, Vertex* top){
00131 if (v==top)
00132 return;
00133 recomputeTransformations(v->parent, top);
00134 v->transformation=v->parent->transformation*v->parameters;
00135 }
00136
00137
00138 void TreeOptimizer3::recomputeParameters(Vertex*v, Vertex* top){
00139 while (v!=top){
00140 v->parameters=v->parent->transformation.inv()*v->transformation;
00141 v=v->parent;
00142 }
00143 }
00144
00145
00146 TreeOptimizer3::Transformation TreeOptimizer3::getPose(Vertex*v, Vertex* top){
00147 Transformation t(0.,0.,0.,0.,0.,0.);
00148 if (v==top)
00149 return v->transformation;
00150 while (v!=top){
00151 t=v->parameters*t;
00152 v=v->parent;
00153 }
00154 return top->transformation*t;
00155 }
00156
00157 TreeOptimizer3::Rotation TreeOptimizer3::getRotation(Vertex*v, Vertex* top){
00158 Rotation r(0.,0.,0.);
00159 if (v==top)
00160 return v->transformation.rotation();
00161 while (v!=top){
00162 r=v->parameters.rotation()*r;
00163 v=v->parent;
00164 }
00165 return top->transformation.rotation()*r;
00166 }
00167
00168
00169
00170 double TreeOptimizer3::error(const Edge* e) const{
00171 const Vertex* v1=e->v1;
00172 const Vertex* v2=e->v2;
00173
00174 Transformation et=e->transformation;
00175 Transformation t1=v1->transformation;
00176 Transformation t2=v2->transformation;
00177
00178 Transformation t12=(t1*et)*t2.inv();
00179 Pose p12=t12.toPoseType();
00180
00181 Pose ps=e->informationMatrix*p12;
00182 double err=p12*ps;
00183 DEBUG(100) << "e(" << v1->id << "," << v2->id << ")" << err << endl;
00184 return err;
00185
00186 }
00187
00188 double TreeOptimizer3::traslationalError(const Edge* e) const{
00189 const Vertex* v1=e->v1;
00190 const Vertex* v2=e->v2;
00191
00192 Transformation et=e->transformation;
00193 Transformation t1=v1->transformation;
00194 Transformation t2=v2->transformation;
00195
00196 Translation t12=(t2.inv()*(t1*et)).translation();
00197 return t12*t12;;
00198
00199 }
00200
00201 double TreeOptimizer3::rotationalError(const Edge* e) const{
00202 const Vertex* v1=e->v1;
00203 const Vertex* v2=e->v2;
00204
00205 Rotation er=e->transformation.rotation();
00206 Rotation r1=v1->transformation.rotation();
00207 Rotation r2=v2->transformation.rotation();
00208
00209 Rotation r12=r2.inverse()*(r1*er);
00210 double r=r12.angle();
00211 return r*r;
00212 }
00213
00214
00215 double TreeOptimizer3::loopError(const Edge* e) const{
00216 double err=0;
00217 const Vertex* v=e->v1;
00218 while (v!=e->top){
00219 err+=error(v->parentEdge);
00220 v=v->parent;
00221 }
00222 v=e->v2;
00223 while (v==e->top){
00224 err+=error(v->parentEdge);
00225 v=v->parent;
00226 }
00227 if (e->v2->parentEdge!=e && e->v1->parentEdge!=e)
00228 err+=error(e);
00229 return err;
00230 }
00231
00232 double TreeOptimizer3::loopRotationalError(const Edge* e) const{
00233 double err=0;
00234 const Vertex* v=e->v1;
00235 while (v!=e->top){
00236 err+=rotationalError(v->parentEdge);
00237 v=v->parent;
00238 }
00239 v=e->v2;
00240 while (v!=e->top){
00241 err+=rotationalError(v->parentEdge);
00242 v=v->parent;
00243 }
00244 if (e->v2->parentEdge!=e && e->v1->parentEdge!=e)
00245 err+=rotationalError(e);
00246 return err;
00247 }
00248
00249
00250 double TreeOptimizer3::error(double* mre, double* mte, double* are, double* ate, TreePoseGraph3::EdgeSet* eset) const{
00251 double globalRotError=0.;
00252 double maxRotError=0;
00253 double globalTrasError=0.;
00254 double maxTrasError=0;
00255
00256 int c=0;
00257 if (! eset){
00258 for (TreePoseGraph3::EdgeMap::const_iterator it=edges.begin(); it!=edges.end(); it++){
00259 double re=rotationalError(it->second);
00260 globalRotError+=re;
00261 maxRotError=maxRotError>re?maxRotError:re;
00262 double te=traslationalError(it->second);
00263 globalTrasError+=te;
00264 maxTrasError=maxTrasError>te?maxTrasError:te;
00265 c++;
00266 }
00267 } else {
00268 for (TreePoseGraph3::EdgeSet::const_iterator it=eset->begin(); it!=eset->end(); it++){
00269 const TreePoseGraph3::Edge* edge=*it;
00270 double re=rotationalError(edge);
00271 globalRotError+=re;
00272 maxRotError=maxRotError>re?maxRotError:re;
00273 double te=traslationalError(edge);
00274 globalTrasError+=te;
00275 maxTrasError=maxTrasError>te?maxTrasError:te;
00276 c++;
00277 }
00278 }
00279
00280 if (mte)
00281 *mte=maxTrasError;
00282 if (mre)
00283 *mre=maxRotError;
00284 if (ate)
00285 *ate=globalTrasError/c;
00286 if (are)
00287 *are=globalRotError/c;
00288 return globalRotError+globalTrasError;
00289 }
00290
00291
00292
00293 void TreeOptimizer3::initializeOptimization(EdgeCompareMode mode){
00294 edgeCompareMode=mode;
00295
00296 int sz=maxIndex()+1;
00297 DEBUG(1) << "Size= " << sz << endl;
00298 M.resize(sz);
00299
00300 DEBUG(1) << "allocating M(" << sz << ")" << endl;
00301 iteration=1;
00302
00303
00304 if (sortedEdges!=0){
00305 delete sortedEdges;
00306 sortedEdges=0;
00307 }
00308 sortedEdges=sortEdges();
00309 mpl=maxPathLength();
00310 rotGain=1.;
00311 trasGain=1.;
00312 }
00313
00314 void TreeOptimizer3::initializeOnlineIterations(){
00315 int sz=maxIndex()+1;
00316 DEBUG(1) << "Size= " << sz << endl;
00317 M.resize(sz);
00318 DEBUG(1) << "allocating M(" << sz << ")" << endl;
00319 iteration=1;
00320 maxRotationalErrors.clear();
00321 maxTranslationalErrors.clear();
00322 rotGain=1.;
00323 trasGain=1.;
00324 }
00325
00326 void TreeOptimizer3::initializeOnlineOptimization(EdgeCompareMode mode){
00327 edgeCompareMode=mode;
00328
00329 clear();
00330 Vertex* v0=addVertex(0,Pose(0,0,0,0,0,0));
00331 root=v0;
00332 v0->parameters=Transformation(v0->pose);
00333 v0->parentEdge=0;
00334 v0->parent=0;
00335 v0->level=0;
00336 v0->transformation=Transformation(TreePoseGraph3::Pose(0,0,0,0,0,0));
00337 }
00338
00339 void TreeOptimizer3::onStepStart(Edge* e){
00340 DEBUG(5) << "entering edge" << e << endl;
00341 }
00342 void TreeOptimizer3::onStepFinished(Edge* e){
00343 DEBUG(5) << "exiting edge" << e << endl;
00344 }
00345
00346 void TreeOptimizer3::onIterationStart(int iteration){
00347 DEBUG(5) << "entering iteration " << iteration << endl;
00348 }
00349
00350 void TreeOptimizer3::onIterationFinished(int iteration){
00351 DEBUG(5) << "exiting iteration " << iteration << endl;
00352 }
00353
00354 void TreeOptimizer3::onRestartBegin(){}
00355 void TreeOptimizer3::onRestartDone(){}
00356 bool TreeOptimizer3::isDone(){
00357 return false;
00358 }
00359
00360
00361 };