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 #include "rtabmap/core/OdometryF2F.h"
00029 #include "rtabmap/core/OdometryInfo.h"
00030 #include "rtabmap/core/Registration.h"
00031 #include "rtabmap/core/EpipolarGeometry.h"
00032 #include "rtabmap/core/util3d_transforms.h"
00033 #include "rtabmap/utilite/ULogger.h"
00034 #include "rtabmap/utilite/UTimer.h"
00035 #include "rtabmap/utilite/UStl.h"
00036
00037 namespace rtabmap {
00038
00039 OdometryF2F::OdometryF2F(const ParametersMap & parameters) :
00040 Odometry(parameters),
00041 keyFrameThr_(Parameters::defaultOdomKeyFrameThr()),
00042 scanKeyFrameThr_(Parameters::defaultOdomScanKeyFrameThr())
00043 {
00044 registrationPipeline_ = Registration::create(parameters);
00045 Parameters::parse(parameters, Parameters::kOdomKeyFrameThr(), keyFrameThr_);
00046 Parameters::parse(parameters, Parameters::kOdomScanKeyFrameThr(), scanKeyFrameThr_);
00047 UASSERT(keyFrameThr_>=0.0f && keyFrameThr_<=1.0f);
00048 UASSERT(scanKeyFrameThr_>=0.0f && scanKeyFrameThr_<=1.0f);
00049 }
00050
00051 OdometryF2F::~OdometryF2F()
00052 {
00053 delete registrationPipeline_;
00054 }
00055
00056 void OdometryF2F::reset(const Transform & initialPose)
00057 {
00058 Odometry::reset(initialPose);
00059 refFrame_ = Signature();
00060 lastKeyFramePose_.setNull();
00061 }
00062
00063
00064 Transform OdometryF2F::computeTransform(
00065 SensorData & data,
00066 const Transform & guess,
00067 OdometryInfo * info)
00068 {
00069 UTimer timer;
00070 Transform output;
00071 if(!data.rightRaw().empty() && !data.stereoCameraModel().isValidForProjection())
00072 {
00073 UERROR("Calibrated stereo camera required");
00074 return output;
00075 }
00076 if(!data.depthRaw().empty() &&
00077 (data.cameraModels().size() != 1 || !data.cameraModels()[0].isValidForProjection()))
00078 {
00079 UERROR("Calibrated camera required (multi-cameras not supported).");
00080 return output;
00081 }
00082
00083 RegistrationInfo regInfo;
00084
00085 UASSERT(!this->getPose().isNull());
00086 if(lastKeyFramePose_.isNull())
00087 {
00088 lastKeyFramePose_ = this->getPose();
00089 }
00090 Transform motionSinceLastKeyFrame = lastKeyFramePose_.inverse()*this->getPose();
00091
00092 Signature newFrame(data);
00093 if(refFrame_.sensorData().isValid())
00094 {
00095 Signature tmpRefFrame = refFrame_;
00096 output = registrationPipeline_->computeTransformationMod(
00097 tmpRefFrame,
00098 newFrame,
00099 !guess.isNull()?motionSinceLastKeyFrame*guess:Transform(),
00100 ®Info);
00101
00102 if(info && this->isInfoDataFilled())
00103 {
00104 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
00105 EpipolarGeometry::findPairsUnique(tmpRefFrame.getWords(), newFrame.getWords(), pairs);
00106 info->refCorners.resize(pairs.size());
00107 info->newCorners.resize(pairs.size());
00108 std::map<int, int> idToIndex;
00109 int i=0;
00110 for(std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::iterator iter=pairs.begin();
00111 iter!=pairs.end();
00112 ++iter)
00113 {
00114 info->refCorners[i] = iter->second.first.pt;
00115 info->newCorners[i] = iter->second.second.pt;
00116 idToIndex.insert(std::make_pair(iter->first, i));
00117 ++i;
00118 }
00119 info->cornerInliers.resize(regInfo.inliersIDs.size(), 1);
00120 i=0;
00121 for(; i<(int)regInfo.inliersIDs.size(); ++i)
00122 {
00123 info->cornerInliers[i] = idToIndex.at(regInfo.inliersIDs[i]);
00124 }
00125
00126 Transform t = this->getPose()*motionSinceLastKeyFrame.inverse();
00127 for(std::multimap<int, cv::Point3f>::const_iterator iter=tmpRefFrame.getWords3().begin(); iter!=tmpRefFrame.getWords3().end(); ++iter)
00128 {
00129 info->localMap.insert(std::make_pair(iter->first, util3d::transformPoint(iter->second, t)));
00130 }
00131 info->words = newFrame.getWords();
00132 }
00133 }
00134 else
00135 {
00136
00137 output = Transform::getIdentity();
00138
00139 regInfo.variance = 9999;
00140 }
00141
00142 if(!output.isNull())
00143 {
00144 output = motionSinceLastKeyFrame.inverse() * output;
00145
00146
00147 if( (registrationPipeline_->isImageRequired() && (keyFrameThr_ == 0 || float(regInfo.inliers) <= keyFrameThr_*float(refFrame_.sensorData().keypoints().size()))) ||
00148 (registrationPipeline_->isScanRequired() && (scanKeyFrameThr_ == 0 || regInfo.icpInliersRatio <= scanKeyFrameThr_)))
00149 {
00150 UDEBUG("Update key frame");
00151 int features = newFrame.getWordsDescriptors().size();
00152 if(features == 0)
00153 {
00154 newFrame = Signature(data);
00155
00156 Signature dummy;
00157 registrationPipeline_->computeTransformationMod(
00158 newFrame,
00159 dummy);
00160 features = (int)newFrame.sensorData().keypoints().size();
00161 }
00162
00163 if((features >= registrationPipeline_->getMinVisualCorrespondences()) &&
00164 (registrationPipeline_->getMinGeometryCorrespondencesRatio()==0.0f ||
00165 (newFrame.sensorData().laserScanRaw().cols &&
00166 (newFrame.sensorData().laserScanMaxPts() == 0 || float(newFrame.sensorData().laserScanRaw().cols)/float(newFrame.sensorData().laserScanMaxPts())>=registrationPipeline_->getMinGeometryCorrespondencesRatio()))))
00167 {
00168 refFrame_ = newFrame;
00169
00170 refFrame_.setWords(std::multimap<int, cv::KeyPoint>());
00171 refFrame_.setWords3(std::multimap<int, cv::Point3f>());
00172 refFrame_.setWordsDescriptors(std::multimap<int, cv::Mat>());
00173
00174
00175 lastKeyFramePose_.setNull();
00176 }
00177 else
00178 {
00179 if (!refFrame_.sensorData().isValid())
00180 {
00181
00182 output.setNull();
00183 }
00184
00185 if(features < registrationPipeline_->getMinVisualCorrespondences())
00186 {
00187 UWARN("Too low 2D features (%d), keeping last key frame...", features);
00188 }
00189
00190 if(registrationPipeline_->getMinGeometryCorrespondencesRatio()>0.0f && newFrame.sensorData().laserScanRaw().cols==0)
00191 {
00192 UWARN("Too low scan points (%d), keeping last key frame...", newFrame.sensorData().laserScanRaw().cols);
00193 }
00194 else if(registrationPipeline_->getMinGeometryCorrespondencesRatio()>0.0f && newFrame.sensorData().laserScanMaxPts() != 0 && float(newFrame.sensorData().laserScanRaw().cols)/float(newFrame.sensorData().laserScanMaxPts())<registrationPipeline_->getMinGeometryCorrespondencesRatio())
00195 {
00196 UWARN("Too low scan points ratio (%d < %d), keeping last key frame...", float(newFrame.sensorData().laserScanRaw().cols)/float(newFrame.sensorData().laserScanMaxPts()), registrationPipeline_->getMinGeometryCorrespondencesRatio());
00197 }
00198 }
00199 }
00200 }
00201 else if(!regInfo.rejectedMsg.empty())
00202 {
00203 UWARN("Registration failed: \"%s\"", regInfo.rejectedMsg.c_str());
00204 }
00205
00206 data.setFeatures(newFrame.sensorData().keypoints(), newFrame.sensorData().descriptors());
00207
00208 if(info)
00209 {
00210 info->type = 1;
00211 info->variance = regInfo.variance;
00212 info->inliers = regInfo.inliers;
00213 info->icpInliersRatio = regInfo.icpInliersRatio;
00214 info->matches = regInfo.matches;
00215 info->features = newFrame.sensorData().keypoints().size();
00216 }
00217
00218 UINFO("Odom update time = %fs lost=%s inliers=%d, ref frame corners=%d, transform accepted=%s",
00219 timer.elapsed(),
00220 output.isNull()?"true":"false",
00221 (int)regInfo.inliers,
00222 (int)newFrame.sensorData().keypoints().size(),
00223 !output.isNull()?"true":"false");
00224
00225 return output;
00226 }
00227
00228 }