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 #include "rtabmap/core/Graph.h"
00028
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UStl.h>
00031 #include <rtabmap/utilite/UMath.h>
00032 #include <rtabmap/utilite/UConversion.h>
00033 #include <rtabmap/utilite/UTimer.h>
00034 #include <set>
00035
00036 #include <rtabmap/core/OptimizerGTSAM.h>
00037
00038 #ifdef RTABMAP_GTSAM
00039 #include <gtsam/geometry/Pose2.h>
00040 #include <gtsam/geometry/Pose3.h>
00041 #include <gtsam/inference/Key.h>
00042 #include <gtsam/inference/Symbol.h>
00043 #include <gtsam/slam/PriorFactor.h>
00044 #include <gtsam/slam/BetweenFactor.h>
00045 #include <gtsam/nonlinear/NonlinearFactorGraph.h>
00046 #include <gtsam/nonlinear/GaussNewtonOptimizer.h>
00047 #include <gtsam/nonlinear/DoglegOptimizer.h>
00048 #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
00049 #include <gtsam/nonlinear/NonlinearOptimizer.h>
00050 #include <gtsam/nonlinear/Marginals.h>
00051 #include <gtsam/nonlinear/Values.h>
00052
00053 #ifdef RTABMAP_VERTIGO
00054 #include "vertigo/gtsam/betweenFactorMaxMix.h"
00055 #include "vertigo/gtsam/betweenFactorSwitchable.h"
00056 #include "vertigo/gtsam/switchVariableLinear.h"
00057 #include "vertigo/gtsam/switchVariableSigmoid.h"
00058 #endif
00059 #endif // end RTABMAP_GTSAM
00060
00061 namespace rtabmap {
00062
00063 bool OptimizerGTSAM::available()
00064 {
00065 #ifdef RTABMAP_GTSAM
00066 return true;
00067 #else
00068 return false;
00069 #endif
00070 }
00071
00072 std::map<int, Transform> OptimizerGTSAM::optimize(
00073 int rootId,
00074 const std::map<int, Transform> & poses,
00075 const std::multimap<int, Link> & edgeConstraints,
00076 std::list<std::map<int, Transform> > * intermediateGraphes,
00077 double * finalError,
00078 int * iterationsDone)
00079 {
00080 std::map<int, Transform> optimizedPoses;
00081 #ifdef RTABMAP_GTSAM
00082
00083 #ifndef RTABMAP_VERTIGO
00084 if(this->isRobust())
00085 {
00086 UWARN("Vertigo robust optimization is not available! Robust optimization is now disabled.");
00087 setRobust(false);
00088 }
00089 #endif
00090
00091 UDEBUG("Optimizing graph...");
00092 if(edgeConstraints.size()>=1 && poses.size()>=2 && iterations() > 0)
00093 {
00094 gtsam::NonlinearFactorGraph graph;
00095
00096
00097 UASSERT(uContains(poses, rootId));
00098 const Transform & initialPose = poses.at(rootId);
00099 if(isSlam2d())
00100 {
00101 gtsam::noiseModel::Diagonal::shared_ptr priorNoise = gtsam::noiseModel::Diagonal::Sigmas(gtsam::Vector3(0.01, 0.01, 0.01));
00102 graph.add(gtsam::PriorFactor<gtsam::Pose2>(rootId, gtsam::Pose2(initialPose.x(), initialPose.y(), initialPose.theta()), priorNoise));
00103 }
00104 else
00105 {
00106 gtsam::noiseModel::Diagonal::shared_ptr priorNoise = gtsam::noiseModel::Diagonal::Sigmas((gtsam::Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4).finished());
00107 graph.add(gtsam::PriorFactor<gtsam::Pose3>(rootId, gtsam::Pose3(initialPose.toEigen4d()), priorNoise));
00108 }
00109
00110 UDEBUG("fill poses to gtsam...");
00111 gtsam::Values initialEstimate;
00112 for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
00113 {
00114 UASSERT(!iter->second.isNull());
00115 if(isSlam2d())
00116 {
00117 initialEstimate.insert(iter->first, gtsam::Pose2(iter->second.x(), iter->second.y(), iter->second.theta()));
00118 }
00119 else
00120 {
00121 initialEstimate.insert(iter->first, gtsam::Pose3(iter->second.toEigen4d()));
00122 }
00123 }
00124
00125 UDEBUG("fill edges to gtsam...");
00126 int switchCounter = poses.rbegin()->first+1;
00127 for(std::multimap<int, Link>::const_iterator iter=edgeConstraints.begin(); iter!=edgeConstraints.end(); ++iter)
00128 {
00129 int id1 = iter->first;
00130 int id2 = iter->second.to();
00131
00132 UASSERT(!iter->second.transform().isNull());
00133
00134 #ifdef RTABMAP_VERTIGO
00135 if(this->isRobust() &&
00136 iter->second.type()!=Link::kNeighbor &&
00137 iter->second.type() != Link::kNeighborMerged)
00138 {
00139
00140
00141
00142
00143
00144 double prior = 1.0;
00145 initialEstimate.insert(gtsam::Symbol('s',switchCounter), vertigo::SwitchVariableLinear(prior));
00146
00147
00148
00149
00150
00151
00152 gtsam::noiseModel::Diagonal::shared_ptr switchPriorModel = gtsam::noiseModel::Diagonal::Sigmas(gtsam::Vector1(1.0));
00153 graph.add(gtsam::PriorFactor<vertigo::SwitchVariableLinear> (gtsam::Symbol('s',switchCounter), vertigo::SwitchVariableLinear(prior), switchPriorModel));
00154 }
00155 #endif
00156
00157 if(isSlam2d())
00158 {
00159 Eigen::Matrix<double, 3, 3> information = Eigen::Matrix<double, 3, 3>::Identity();
00160 if(!isCovarianceIgnored())
00161 {
00162
00163 information(0,0) = iter->second.infMatrix().at<double>(0,0)/1000.0;
00164 information(0,1) = iter->second.infMatrix().at<double>(0,1)/1000.0;
00165 information(0,2) = iter->second.infMatrix().at<double>(0,5)/1000.0;
00166 information(1,0) = iter->second.infMatrix().at<double>(1,0)/1000.0;
00167 information(1,1) = iter->second.infMatrix().at<double>(1,1)/1000.0;
00168 information(1,2) = iter->second.infMatrix().at<double>(1,5)/1000.0;
00169 information(2,0) = iter->second.infMatrix().at<double>(5,0)/1000.0;
00170 information(2,1) = iter->second.infMatrix().at<double>(5,1)/1000.0;
00171 information(2,2) = iter->second.infMatrix().at<double>(5,5)/1000.0;
00172 }
00173 gtsam::noiseModel::Gaussian::shared_ptr model = gtsam::noiseModel::Gaussian::Information(information);
00174
00175 #ifdef RTABMAP_VERTIGO
00176 if(this->isRobust() &&
00177 iter->second.type()!=Link::kNeighbor &&
00178 iter->second.type() != Link::kNeighborMerged)
00179 {
00180
00181 graph.add(vertigo::BetweenFactorSwitchableLinear<gtsam::Pose2>(id1, id2, gtsam::Symbol('s', switchCounter++), gtsam::Pose2(iter->second.transform().x(), iter->second.transform().y(), iter->second.transform().theta()), model));
00182 }
00183 else
00184 #endif
00185 {
00186 graph.add(gtsam::BetweenFactor<gtsam::Pose2>(id1, id2, gtsam::Pose2(iter->second.transform().x(), iter->second.transform().y(), iter->second.transform().theta()), model));
00187 }
00188 }
00189 else
00190 {
00191 Eigen::Matrix<double, 6, 6> information = Eigen::Matrix<double, 6, 6>::Identity();
00192 if(!isCovarianceIgnored())
00193 {
00194 memcpy(information.data(), iter->second.infMatrix().data, iter->second.infMatrix().total()*sizeof(double));
00195
00196 information = information / 1000.0;
00197 }
00198
00199 gtsam::noiseModel::Gaussian::shared_ptr model = gtsam::noiseModel::Gaussian::Information(information);
00200
00201 #ifdef RTABMAP_VERTIGO
00202 if(this->isRobust() &&
00203 iter->second.type()!=Link::kNeighbor &&
00204 iter->second.type() != Link::kNeighborMerged)
00205 {
00206
00207 graph.add(vertigo::BetweenFactorSwitchableLinear<gtsam::Pose3>(id1, id2, gtsam::Symbol('s', switchCounter++), gtsam::Pose3(iter->second.transform().toEigen4d()), model));
00208 }
00209 else
00210 #endif
00211 {
00212 graph.add(gtsam::BetweenFactor<gtsam::Pose3>(id1, id2, gtsam::Pose3(iter->second.transform().toEigen4d()), model));
00213 }
00214 }
00215 }
00216
00217 UDEBUG("create optimizer");
00218 gtsam::GaussNewtonParams parameters;
00219 parameters.relativeErrorTol = epsilon();
00220 parameters.maxIterations = iterations();
00221 gtsam::GaussNewtonOptimizer optimizer(graph, initialEstimate, parameters);
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231 UINFO("GTSAM optimizing begin (max iterations=%d, robust=%d)", iterations(), isRobust()?1:0);
00232 UTimer timer;
00233 int it = 0;
00234 double lastError = 0.0;
00235 for(int i=0; i<iterations(); ++i)
00236 {
00237 if(intermediateGraphes && i > 0)
00238 {
00239 std::map<int, Transform> tmpPoses;
00240 for(gtsam::Values::const_iterator iter=optimizer.values().begin(); iter!=optimizer.values().end(); ++iter)
00241 {
00242 if(iter->value.dim() > 1)
00243 {
00244 if(isSlam2d())
00245 {
00246 gtsam::Pose2 p = iter->value.cast<gtsam::Pose2>();
00247 tmpPoses.insert(std::make_pair((int)iter->key, Transform(p.x(), p.y(), p.theta())));
00248 }
00249 else
00250 {
00251 gtsam::Pose3 p = iter->value.cast<gtsam::Pose3>();
00252 tmpPoses.insert(std::make_pair((int)iter->key, Transform::fromEigen4d(p.matrix())));
00253 }
00254 }
00255 }
00256 intermediateGraphes->push_back(tmpPoses);
00257 }
00258 try
00259 {
00260 optimizer.iterate();
00261 ++it;
00262 }
00263 catch(gtsam::IndeterminantLinearSystemException & e)
00264 {
00265 UERROR("GTSAM exception caught: %s", e.what());
00266 return optimizedPoses;
00267 }
00268
00269
00270 double error = optimizer.error();
00271 UDEBUG("iteration %d error =%f", i+1, error);
00272 double errorDelta = lastError - error;
00273 if(i>0 && errorDelta < this->epsilon())
00274 {
00275 if(errorDelta < 0)
00276 {
00277 UDEBUG("Negative improvement?! Ignore and continue optimizing... (%f < %f)", errorDelta, this->epsilon());
00278 }
00279 else
00280 {
00281 UINFO("Stop optimizing, not enough improvement (%f < %f)", errorDelta, this->epsilon());
00282 break;
00283 }
00284 }
00285 else if(i==0 && error < this->epsilon())
00286 {
00287 UINFO("Stop optimizing, error is already under epsilon (%f < %f)", error, this->epsilon());
00288 break;
00289 }
00290 lastError = error;
00291 }
00292 if(finalError)
00293 {
00294 *finalError = lastError;
00295 }
00296 if(iterationsDone)
00297 {
00298 *iterationsDone = it;
00299 }
00300 UINFO("GTSAM optimizing end (%d iterations done, error=%f (initial=%f final=%f), time=%f s)", optimizer.iterations(), optimizer.error(), graph.error(initialEstimate), graph.error(optimizer.values()), timer.ticks());
00301
00302 for(gtsam::Values::const_iterator iter=optimizer.values().begin(); iter!=optimizer.values().end(); ++iter)
00303 {
00304 if(iter->value.dim() > 1)
00305 {
00306 if(isSlam2d())
00307 {
00308 gtsam::Pose2 p = iter->value.cast<gtsam::Pose2>();
00309 optimizedPoses.insert(std::make_pair((int)iter->key, Transform(p.x(), p.y(), p.theta())));
00310 }
00311 else
00312 {
00313 gtsam::Pose3 p = iter->value.cast<gtsam::Pose3>();
00314 optimizedPoses.insert(std::make_pair((int)iter->key, Transform::fromEigen4d(p.matrix())));
00315 }
00316 }
00317 }
00318 }
00319 else if(poses.size() == 1 || iterations() <= 0)
00320 {
00321 optimizedPoses = poses;
00322 }
00323 else
00324 {
00325 UWARN("This method should be called at least with 1 pose!");
00326 }
00327 UDEBUG("Optimizing graph...end!");
00328 #else
00329 UERROR("Not built with GTSAM support!");
00330 #endif
00331 return optimizedPoses;
00332 }
00333
00334 }