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/OptimizerCVSBA.h>
00037
00038 #ifdef RTABMAP_CVSBA
00039 #include <cvsba/cvsba.h>
00040 #include "rtabmap/core/util3d_motion_estimation.h"
00041 #include "rtabmap/core/util3d_transforms.h"
00042 #include "rtabmap/core/util3d_correspondences.h"
00043 #endif
00044
00045 namespace rtabmap {
00046
00047 bool OptimizerCVSBA::available()
00048 {
00049 #ifdef RTABMAP_CVSBA
00050 return true;
00051 #else
00052 return false;
00053 #endif
00054 }
00055
00056 std::map<int, Transform> OptimizerCVSBA::optimizeBA(
00057 int rootId,
00058 const std::map<int, Transform> & poses,
00059 const std::multimap<int, Link> & links,
00060 const std::map<int, Signature> & signatures)
00061 {
00062 #ifdef RTABMAP_CVSBA
00063
00064 cvsba::Sba sba;
00065
00066
00067 cvsba::Sba::Params params ;
00068 params.type = cvsba::Sba::MOTIONSTRUCTURE;
00069 params.iterations = this->iterations();
00070 params.minError = this->epsilon();
00071 params.fixedIntrinsics = 5;
00072 params.fixedDistortion = 5;
00073 params.verbose=ULogger::level() <= ULogger::kInfo;
00074 sba.setParams(params);
00075
00076 std::map<int, Transform> frames = poses;
00077
00078 std::vector<cv::Mat> cameraMatrix(frames.size());
00079 std::vector<cv::Mat> R(frames.size());
00080 std::vector<cv::Mat> T(frames.size());
00081 std::vector<cv::Mat> distCoeffs(frames.size());
00082 std::map<int, int> frameIdToIndex;
00083 std::map<int, CameraModel> models;
00084 int oi=0;
00085 for(std::map<int, Transform>::iterator iter=frames.begin(); iter!=frames.end(); )
00086 {
00087 CameraModel model;
00088 if(uContains(signatures, iter->first))
00089 {
00090 if(signatures.at(iter->first).sensorData().cameraModels().size() == 1 && signatures.at(iter->first).sensorData().cameraModels().at(0).isValidForProjection())
00091 {
00092 model = signatures.at(iter->first).sensorData().cameraModels()[0];
00093 }
00094 else if(signatures.at(iter->first).sensorData().stereoCameraModel().isValidForProjection())
00095 {
00096 model = signatures.at(iter->first).sensorData().stereoCameraModel().left();
00097 }
00098 else
00099 {
00100 UERROR("Missing calibration for node %d", iter->first);
00101 }
00102 }
00103 else
00104 {
00105 UERROR("Did not find node %d in cache", iter->first);
00106 }
00107
00108 if(model.isValidForProjection())
00109 {
00110 frameIdToIndex.insert(std::make_pair(iter->first, oi));
00111
00112 cameraMatrix[oi] = model.K();
00113 if(model.D().cols != 5)
00114 {
00115 distCoeffs[oi] = cv::Mat::zeros(1, 5, CV_64FC1);
00116 UWARN("Camera model %d: Distortion coefficients are not 5, setting all them to 0 (assuming no distortion)", iter->first);
00117 }
00118 else
00119 {
00120 distCoeffs[oi] = model.D();
00121 }
00122
00123 Transform t = (iter->second * model.localTransform()).inverse();
00124
00125 R[oi] = (cv::Mat_<double>(3,3) <<
00126 (double)t.r11(), (double)t.r12(), (double)t.r13(),
00127 (double)t.r21(), (double)t.r22(), (double)t.r23(),
00128 (double)t.r31(), (double)t.r32(), (double)t.r33());
00129 T[oi] = (cv::Mat_<double>(1,3) << (double)t.x(), (double)t.y(), (double)t.z());
00130 ++oi;
00131
00132 models.insert(std::make_pair(iter->first, model));
00133
00134 UDEBUG("Pose %d = %s", iter->first, t.prettyPrint().c_str());
00135
00136 ++iter;
00137 }
00138 else
00139 {
00140 frames.erase(iter++);
00141 }
00142 }
00143 cameraMatrix.resize(oi);
00144 R.resize(oi);
00145 T.resize(oi);
00146 distCoeffs.resize(oi);
00147
00148 std::map<int, cv::Point3f> points3DMap;
00149 std::map<int, std::map<int, cv::Point2f> > wordReferences;
00150 computeBACorrespondences(frames, links, signatures, points3DMap, wordReferences);
00151
00152 UDEBUG("points=%d frames=%d", (int)wordReferences.size(), (int)frames.size());
00153 std::vector<cv::Point3f> points(wordReferences.size());
00154 std::vector<std::vector<cv::Point2f> > imagePoints(frames.size());
00155 std::vector<std::vector<int> > visibility(frames.size());
00156 for(unsigned int i=0; i<frames.size(); ++i)
00157 {
00158 imagePoints[i].resize(wordReferences.size(), cv::Point2f(std::numeric_limits<float>::quiet_NaN(), std::numeric_limits<float>::quiet_NaN()));
00159 visibility[i].resize(wordReferences.size(), 0);
00160 }
00161 int i=0;
00162 for(std::map<int, std::map<int, cv::Point2f> >::iterator iter = wordReferences.begin(); iter!=wordReferences.end(); ++iter)
00163 {
00164 points[i] = points3DMap.at(iter->first);
00165
00166 for(std::map<int, cv::Point2f>::const_iterator jter=iter->second.begin(); jter!=iter->second.end(); ++jter)
00167 {
00168 imagePoints[frameIdToIndex.at(jter->first)][i] = jter->second;
00169 visibility[frameIdToIndex.at(jter->first)][i] = 1;
00170 }
00171 ++i;
00172 }
00173
00174
00175 try
00176 {
00177 sba.run( points, imagePoints, visibility, cameraMatrix, R, T, distCoeffs);
00178 }
00179 catch(cv::Exception & e)
00180 {
00181 UERROR("Running SBA... error! %s", e.what());
00182 return std::map<int, Transform>();
00183 }
00184
00185
00186 i=0;
00187 for(std::map<int, Transform>::iterator iter=frames.begin(); iter!=frames.end(); ++iter)
00188 {
00189 Transform t(R[i].at<double>(0,0), R[i].at<double>(0,1), R[i].at<double>(0,2), T[i].at<double>(0),
00190 R[i].at<double>(1,0), R[i].at<double>(1,1), R[i].at<double>(1,2), T[i].at<double>(1),
00191 R[i].at<double>(2,0), R[i].at<double>(2,1), R[i].at<double>(2,2), T[i].at<double>(2));
00192
00193 UDEBUG("New pose %d = %s", iter->first, t.prettyPrint().c_str());
00194
00195 iter->second = (models.at(iter->first).localTransform() * t).inverse();
00196
00197 ++i;
00198 }
00199
00200 return frames;
00201
00202 #else
00203 UERROR("RTAB-Map is not built with cvsba!");
00204 return std::map<int, Transform>();
00205 #endif
00206 }
00207
00208 }