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
00037 #include "treeoptimizer3.hh"
00038 #include <fstream>
00039 #include <string>
00040
00041 using namespace std;
00042
00043 namespace AISNavigation {
00044
00045 #define DEBUG(i) \
00046 if (verboseLevel>i) cerr
00047
00048
00049 inline double max3( const double& a, const double& b, const double& c){
00050 double m=a>b?a:b;
00051 return m>c?m:c;
00052 }
00053 inline double min3( const double& a, const double& b, const double& c){
00054 double m=a<b?a:b;
00055 return m<c?m:c;
00056 }
00057
00058
00059 struct NodeInfo{
00060 TreeOptimizer3::Vertex* n;
00061 double translationalWeight;
00062 double rotationalWeight;
00063 int direction;
00064 TreeOptimizer3::Transformation transformation;
00065 TreeOptimizer3::Transformation parameters;
00066 NodeInfo(TreeOptimizer3::Vertex* v=0, double tw=0, double rw=0, int dir=0,
00067 TreeOptimizer3::Transformation t=TreeOptimizer3::Transformation(0,0,0,0,0,0),
00068 TreeOptimizer3::Parameters p=TreeOptimizer3::Transformation(0,0,0,0,0,0)){
00069 n=v;
00070 translationalWeight=tw;
00071 rotationalWeight=rw;
00072 direction=dir;
00073 transformation=t;
00074 parameters=p;
00075 }
00076 };
00077
00078 typedef std::vector<NodeInfo> NodeInfoVector;
00079
00080
00081
00082
00083
00084
00085
00086
00087 void TreeOptimizer3::computePreconditioner(){
00088 for (uint i=0; i<M.size(); i++){
00089 M[i][0]=0;
00090 M[i][1]=0;
00091 }
00092 gamma[0] = gamma[1] = numeric_limits<double>::max();
00093
00094 int edgeCount=0;
00095 for (EdgeSet::iterator it=sortedEdges->begin(); it!=sortedEdges->end(); it++){
00096 edgeCount++;
00097 if (! (edgeCount%1000))
00098 DEBUG(1) << "m";
00099
00100 Edge* e=*it;
00101
00102 InformationMatrix W=e->informationMatrix;
00103
00104 Vertex* top=e->top;
00105 for (int dir=0; dir<2; dir++){
00106 Vertex* n = (dir==0)? e->v1 : e->v2;
00107 while (n!=top){
00108 uint i=n->id;
00109 double rW=min3(W[0][0], W[1][1], W[2][2]);
00110 double tW=min3(W[3][3], W[4][4], W[5][5]);
00111 M[i][0]+=rW;
00112 M[i][1]+=tW;
00113 gamma[0]=gamma[0]<rW?gamma[0]:rW;
00114 gamma[1]=gamma[1]<tW?gamma[1]:tW;
00115 n=n->parent;
00116 }
00117 }
00118
00119 }
00120
00121 if (verboseLevel>1){
00122 for (uint i=0; i<M.size(); i++){
00123 cerr << "M[" << i << "]=" << M[i][0] << " " << M[i][1] << endl;
00124 }
00125 }
00126 }
00127
00128
00129 void TreeOptimizer3::propagateErrors(bool usePreconditioner){
00130 iteration++;
00131 int edgeCount=0;
00132
00133
00134 static NodeInfoVector path;
00135 path.resize(edges.size()+1);
00136 static Rotation zero(0.,0.,0.);
00137
00138 onIterationStart(iteration);
00139 for (EdgeSet::iterator it=sortedEdges->begin(); it!=sortedEdges->end(); it++){
00140 edgeCount++;
00141 if (! (edgeCount%1000))
00142 DEBUG(1) << "c";
00143
00144 if (isDone())
00145 return;
00146
00147 Edge* e=*it;
00148 Vertex* top=e->top;
00149 Vertex* v1=e->v1;
00150 Vertex* v2=e->v2;
00151 int l=e->length;
00152 onStepStart(e);
00153
00154 recomputeTransformations(v1,top);
00155 recomputeTransformations(v2,top);
00156 DEBUG(2) << "Edge: " << v1->id << " " << v2->id << ", top=" << top->id << ", length="<< l <<endl;
00157
00158
00159 int pc=0;
00160 Vertex* aux=v1;
00161 double totTW=0, totRW=0;
00162 while(aux!=top){
00163 int index=aux->id;
00164 double tw=1./(double)l, rw=1./(double)l;
00165 if (usePreconditioner){
00166 tw=1./M[index][0];
00167 rw=1./M[index][1];
00168 }
00169 totTW+=tw;
00170 totRW+=rw;
00171 path[pc++]=NodeInfo(aux,tw,rw,-1,aux->transformation, aux->parameters);
00172 aux=aux->parent;
00173 }
00174 int topIndex=pc;
00175 path[pc++]=NodeInfo(top,0.,0.,0, top->transformation, top->parameters);
00176 pc=l;
00177 aux=v2;
00178 while(aux!=top){
00179 int index=aux->id;
00180 double tw=1./l, rw=1./l;
00181 if (usePreconditioner){
00182 tw=1./M[index][0];
00183 rw=1./M[index][1];
00184 }
00185 totTW+=tw;
00186 totRW+=rw;
00187 path[pc--]=NodeInfo(aux,tw,rw,1,aux->transformation, aux->parameters);
00188 aux=aux->parent;
00189 }
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200 Rotation r1=getRotation(v1, top);
00201 Rotation r2=getRotation(v2, top);
00202 Rotation re=e->transformation.rotation();
00203 Rotation rR=r2.inverse()*(r1*re);
00204
00205 double rotationFactor=(usePreconditioner)?
00206 sqrt(double(l))* min3(e->informationMatrix[0][0],
00207 e->informationMatrix[1][1],
00208 e->informationMatrix[2][2])/
00209 ( gamma[0]* (double)iteration ):
00210 sqrt(double(l))*rotGain/(double)iteration;
00211
00212
00213
00214
00215
00216
00217
00218
00219 if (rotationFactor>1)
00220 rotationFactor=1;
00221
00222 Rotation totalRotation = path[l].transformation.rotation() * rR * path[l].transformation.rotation().inverse();
00223
00224 Translation axis = totalRotation.axis();
00225 double angle=totalRotation.angle();
00226
00227 double cw=0;
00228 for (int i= 1; i<=topIndex; i++){
00229 cw+=path[i-1].rotationalWeight/totRW;
00230 Rotation R=path[i].transformation.rotation();
00231 Rotation B(axis, angle*cw*rotationFactor);
00232 R= B*R;
00233 path[i].transformation.setRotation(R);
00234 }
00235 for (int i= topIndex+1; i<=l; i++){
00236 cw+=path[i].rotationalWeight/totRW;
00237 Rotation R=path[i].transformation.rotation();
00238 Rotation B(axis, angle*cw*rotationFactor);
00239 R= B*R;
00240 path[i].transformation.setRotation(R);
00241 }
00242
00243
00244 for (int i=0; i<topIndex; i++){
00245 Vertex* n=path[i].n;
00246 n->parameters.setRotation(path[i+1].transformation.rotation().inverse()*path[i].transformation.rotation());
00247 }
00248 for (int i= topIndex+1; i<=l; i++){
00249 Vertex* n=path[i].n;
00250 n->parameters.setRotation(path[i-1].transformation.rotation().inverse()*path[i].transformation.rotation());
00251 }
00252
00253
00254
00255
00256
00257 recomputeTransformations(v1,top);
00258 recomputeTransformations(v2,top);
00259
00260
00261
00262
00263 Transformation tr12=v1->transformation*e->transformation;
00264 Translation tR=tr12.translation()-v2->transformation.translation();
00265
00266
00267
00268
00269
00270
00271
00272
00273 double translationFactor=(usePreconditioner)?
00274 trasGain*l*min3(e->informationMatrix[3][3],
00275 e->informationMatrix[4][4],
00276 e->informationMatrix[5][5])/( gamma[1]* (double)iteration):
00277 trasGain*l/(double)iteration;
00278
00279 if (translationFactor>1)
00280 translationFactor=1;
00281 Translation dt=tR*translationFactor;
00282
00283
00284 double lcum=0;
00285 for (int i=topIndex-1; i>=0; i--){
00286 Vertex* n=path[i].n;
00287 lcum-=(usePreconditioner) ? path[i].translationalWeight/totTW : 1./(double)l;
00288 double fraction=lcum;
00289 Translation offset= dt*fraction;
00290 Translation T=n->transformation.translation()+offset;
00291 n->transformation.setTranslation(T);
00292 }
00293
00294
00295 double rcum=0;
00296 for (int i=topIndex+1; i<=l; i++){
00297 Vertex* n=path[i].n;
00298 rcum+=(usePreconditioner) ? path[i].translationalWeight/totTW : 1./(double)l;
00299 double fraction=rcum;
00300 Translation offset= dt*fraction;
00301 Translation T=n->transformation.translation()+offset;
00302 n->transformation.setTranslation(T);
00303 }
00304 assert(fabs(lcum+rcum)-1<1e-6);
00305
00306 recomputeParameters(v1, top);
00307 recomputeParameters(v2, top);
00308
00309
00310
00311 onStepFinished(e);
00312
00313 if (verboseLevel>2){
00314 Rotation newRotResidual=v2->transformation.rotation().inverse()*(v1->transformation.rotation()*re);
00315 Translation newRotResidualAxis=newRotResidual.axis();
00316 double newRotResidualAngle=newRotResidual.angle();
00317 Translation rotResidualAxis=rR.axis();
00318 double rotResidualAngle=rR.angle();
00319 Translation newTransResidual=(v1->transformation*e->transformation).translation()-v2->transformation.translation();
00320
00321 cerr << "RotationalFraction: " << rotationFactor << endl;
00322 cerr << "Rotational residual: "
00323 << " axis " << rotResidualAxis.x() << "\t" << rotResidualAxis.y() << "\t" << rotResidualAxis.z() << " --> "
00324 << " -> " << newRotResidualAxis.x() << "\t" << newRotResidualAxis.y() << "\t" << newRotResidualAxis.z() << endl;
00325 cerr << " angle " << rotResidualAngle << "\t" << newRotResidualAngle << endl;
00326
00327 cerr << "Translational Fraction: " << translationFactor << endl;
00328 cerr << "Translational Residual" << endl;
00329 cerr << " " << tR.x() << "\t" << tR.y() << "\t" << tR.z() << endl;
00330 cerr << " " << newTransResidual.x() << "\t" << newTransResidual.y() << "\t" << newTransResidual.z() << endl;
00331 }
00332
00333 if (verboseLevel>101){
00334 char filename [1000];
00335 sprintf(filename, "po-%02d-%03d-%03d-.dat", iteration, v1->id, v2->id);
00336 recomputeAllTransformations();
00337 saveGnuplot(filename);
00338 }
00339 }
00340 onIterationFinished(iteration);
00341 }
00342
00343 };