OdometryF2F.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
34 #include "rtabmap/utilite/UTimer.h"
35 #include "rtabmap/utilite/UStl.h"
36 
37 namespace rtabmap {
38 
40  Odometry(parameters),
41  keyFrameThr_(Parameters::defaultOdomKeyFrameThr()),
42  visKeyFrameThr_(Parameters::defaultOdomVisKeyFrameThr()),
43  scanKeyFrameThr_(Parameters::defaultOdomScanKeyFrameThr())
44 {
46  Parameters::parse(parameters, Parameters::kOdomKeyFrameThr(), keyFrameThr_);
47  Parameters::parse(parameters, Parameters::kOdomVisKeyFrameThr(), visKeyFrameThr_);
48  Parameters::parse(parameters, Parameters::kOdomScanKeyFrameThr(), scanKeyFrameThr_);
49  UASSERT(keyFrameThr_>=0.0f && keyFrameThr_<=1.0f);
52 
53  parameters_ = parameters;
54 }
55 
57 {
58  delete registrationPipeline_;
59 }
60 
61 void OdometryF2F::reset(const Transform & initialPose)
62 {
63  Odometry::reset(initialPose);
64  refFrame_ = Signature();
66 }
67 
68 // return not null transform if odometry is correctly computed
70  SensorData & data,
71  const Transform & guess,
72  OdometryInfo * info)
73 {
74  UTimer timer;
75  Transform output;
76  if(!data.rightRaw().empty() && !data.stereoCameraModel().isValidForProjection())
77  {
78  UERROR("Calibrated stereo camera required");
79  return output;
80  }
81  if(!data.depthRaw().empty() &&
82  (data.cameraModels().size() != 1 || !data.cameraModels()[0].isValidForProjection()))
83  {
84  UERROR("Calibrated camera required (multi-cameras not supported).");
85  return output;
86  }
87 
88  bool addKeyFrame = false;
89  RegistrationInfo regInfo;
90 
91  UASSERT(!this->getPose().isNull());
93  {
94  lastKeyFramePose_ = this->getPose(); // reset to current pose
95  }
96  Transform motionSinceLastKeyFrame = lastKeyFramePose_.inverse()*this->getPose();
97 
98  Signature newFrame(data);
100  {
101  float maxCorrespondenceDistance = 0.0f;
102  float pmOutlierRatio = 0.0f;
103  if(guess.isNull() &&
106  this->framesProcessed() < 2)
107  {
108  // only on initialization (first frame to register), increase icp max correspondences in case the robot is already moving
109  maxCorrespondenceDistance = Parameters::defaultIcpMaxCorrespondenceDistance();
110  pmOutlierRatio = Parameters::defaultIcpPMOutlierRatio();
111  Parameters::parse(parameters_, Parameters::kIcpMaxCorrespondenceDistance(), maxCorrespondenceDistance);
112  Parameters::parse(parameters_, Parameters::kIcpPMOutlierRatio(), pmOutlierRatio);
113  ParametersMap params;
114  params.insert(ParametersPair(Parameters::kIcpMaxCorrespondenceDistance(), uNumber2Str(maxCorrespondenceDistance*3.0f)));
115  params.insert(ParametersPair(Parameters::kIcpPMOutlierRatio(), uNumber2Str(0.95f)));
117  }
118 
119  Signature tmpRefFrame = refFrame_;
121  tmpRefFrame,
122  newFrame,
123  // special case for ICP-only odom, set guess to identity if we just started or reset
124  !guess.isNull()?motionSinceLastKeyFrame*guess:!registrationPipeline_->isImageRequired()&&this->framesProcessed()<2?motionSinceLastKeyFrame:Transform(),
125  &regInfo);
126 
127  if(maxCorrespondenceDistance>0.0f)
128  {
129  // set it back
130  ParametersMap params;
131  params.insert(ParametersPair(Parameters::kIcpMaxCorrespondenceDistance(), uNumber2Str(maxCorrespondenceDistance)));
132  params.insert(ParametersPair(Parameters::kIcpPMOutlierRatio(), uNumber2Str(pmOutlierRatio)));
134  }
135 
136  if(output.isNull() && !guess.isNull() && registrationPipeline_->isImageRequired())
137  {
138  tmpRefFrame = refFrame_;
139  // reset matches, but keep already extracted features in newFrame.sensorData()
140  newFrame.setWords(std::multimap<int, cv::KeyPoint>());
141  newFrame.setWords3(std::multimap<int, cv::Point3f>());
142  newFrame.setWordsDescriptors(std::multimap<int, cv::Mat>());
143  UWARN("Failed to find a transformation with the provided guess (%s), trying again without a guess.", guess.prettyPrint().c_str());
144  // If optical flow is used, switch temporary to feature matching
145  int visCorTypeBackup = Parameters::defaultVisCorType();
146  Parameters::parse(parameters_, Parameters::kVisCorType(), visCorTypeBackup);
147  if(visCorTypeBackup == 1)
148  {
149  ParametersMap params;
150  params.insert(ParametersPair(Parameters::kVisCorType(), "0"));
152  }
153 
155  tmpRefFrame,
156  newFrame,
157  Transform(), // null guess
158  &regInfo);
159 
160  if(visCorTypeBackup == 1)
161  {
162  ParametersMap params;
163  params.insert(ParametersPair(Parameters::kVisCorType(), "1"));
165  }
166 
167  if(output.isNull())
168  {
169  UWARN("Trial with no guess still fail.");
170  }
171  else
172  {
173  UWARN("Trial with no guess succeeded.");
174  }
175  }
176 
177  if(info && this->isInfoDataFilled())
178  {
179  std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
180  EpipolarGeometry::findPairsUnique(tmpRefFrame.getWords(), newFrame.getWords(), pairs);
181  info->refCorners.resize(pairs.size());
182  info->newCorners.resize(pairs.size());
183  std::map<int, int> idToIndex;
184  int i=0;
185  for(std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::iterator iter=pairs.begin();
186  iter!=pairs.end();
187  ++iter)
188  {
189  info->refCorners[i] = iter->second.first.pt;
190  info->newCorners[i] = iter->second.second.pt;
191  idToIndex.insert(std::make_pair(iter->first, i));
192  ++i;
193  }
194  info->cornerInliers.resize(regInfo.inliersIDs.size(), 1);
195  i=0;
196  for(; i<(int)regInfo.inliersIDs.size(); ++i)
197  {
198  info->cornerInliers[i] = idToIndex.at(regInfo.inliersIDs[i]);
199  }
200 
201  Transform t = this->getPose()*motionSinceLastKeyFrame.inverse();
202  for(std::multimap<int, cv::Point3f>::const_iterator iter=tmpRefFrame.getWords3().begin(); iter!=tmpRefFrame.getWords3().end(); ++iter)
203  {
204  info->localMap.insert(std::make_pair(iter->first, util3d::transformPoint(iter->second, t)));
205  }
206  info->localMapSize = tmpRefFrame.getWords3().size();
207  info->words = newFrame.getWords();
208 
209  info->localScanMapSize = tmpRefFrame.sensorData().laserScanRaw().size();
210 
212  }
213  }
214  else
215  {
216  //return Identity
217  output = Transform::getIdentity();
218  // a very high variance tells that the new pose is not linked with the previous one
219  regInfo.covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0;
220  }
221 
222  if(!output.isNull())
223  {
224  output = motionSinceLastKeyFrame.inverse() * output;
225 
226  // new key-frame?
228  (keyFrameThr_ == 0.0f ||
229  visKeyFrameThr_ == 0 ||
230  float(regInfo.inliers) <= keyFrameThr_*float(refFrame_.sensorData().keypoints().size()) ||
231  regInfo.inliers <= visKeyFrameThr_)) ||
233  {
234  UDEBUG("Update key frame");
235  int features = newFrame.getWordsDescriptors().size();
236  if(registrationPipeline_->isImageRequired() && features == 0)
237  {
238  newFrame = Signature(data);
239  // this will generate features only for the first frame or if optical flow was used (no 3d words)
240  Signature dummy;
242  newFrame,
243  dummy);
244  features = (int)newFrame.sensorData().keypoints().size();
245  }
246 
249  (newFrame.sensorData().laserScanRaw().size() &&
251  {
252  refFrame_ = newFrame;
253 
254  refFrame_.setWords(std::multimap<int, cv::KeyPoint>());
255  refFrame_.setWords3(std::multimap<int, cv::Point3f>());
256  refFrame_.setWordsDescriptors(std::multimap<int, cv::Mat>());
257 
258  //reset motion
260 
261  addKeyFrame = true;
262  }
263  else
264  {
265  if (!refFrame_.sensorData().isValid())
266  {
267  // Don't send odometry if we don't have a keyframe yet
268  output.setNull();
269  }
270 
271  if(features < registrationPipeline_->getMinVisualCorrespondences())
272  {
273  UWARN("Too low 2D features (%d), keeping last key frame...", features);
274  }
275 
277  {
278  UWARN("Too low scan points (%d), keeping last key frame...", newFrame.sensorData().laserScanRaw().size());
279  }
281  {
282  UWARN("Too low scan points ratio (%d < %d), keeping last key frame...", float(newFrame.sensorData().laserScanRaw().size())/float(newFrame.sensorData().laserScanRaw().maxPoints()), registrationPipeline_->getMinGeometryCorrespondencesRatio());
283  }
284  }
285  }
286  }
287  else if(!regInfo.rejectedMsg.empty())
288  {
289  UWARN("Registration failed: \"%s\"", regInfo.rejectedMsg.c_str());
290  }
291 
292  data.setFeatures(newFrame.sensorData().keypoints(), newFrame.sensorData().keypoints3D(), newFrame.sensorData().descriptors());
293 
294  if(info)
295  {
296  info->type = kTypeF2F;
297  info->features = newFrame.sensorData().keypoints().size();
298  info->keyFrameAdded = addKeyFrame;
299  if(this->isInfoDataFilled())
300  {
301  info->reg = regInfo;
302  }
303  else
304  {
305  info->reg = regInfo.copyWithoutData();
306  }
307  }
308 
309  UINFO("Odom update time = %fs lost=%s inliers=%d, ref frame corners=%d, transform accepted=%s",
310  timer.elapsed(),
311  output.isNull()?"true":"false",
312  (int)regInfo.inliers,
313  (int)newFrame.sensorData().keypoints().size(),
314  !output.isNull()?"true":"false");
315 
316  return output;
317 }
318 
319 } // namespace rtabmap
const std::multimap< int, cv::Point3f > & getWords3() const
Definition: Signature.h:128
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:446
int getMinVisualCorrespondences() const
std::vector< cv::Point2f > refCorners
Definition: OdometryInfo.h:120
unsigned int framesProcessed() const
Definition: Odometry.h:75
Definition: UTimer.h:46
std::string prettyPrint() const
Definition: Transform.cpp:274
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
float getMinGeometryCorrespondencesRatio() const
double elapsed()
Definition: UTimer.h:75
const std::multimap< int, cv::KeyPoint > & getWords() const
Definition: Signature.h:108
void setWords3(const std::multimap< int, cv::Point3f > &words3)
Definition: Signature.h:115
f
bool isInfoDataFilled() const
Definition: Odometry.h:72
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:182
void setWords(const std::multimap< int, cv::KeyPoint > &words)
Definition: Signature.cpp:231
Transform computeTransformationMod(Signature &from, Signature &to, Transform guess=Transform::getIdentity(), RegistrationInfo *info=0) const
std::map< int, cv::Point3f > localMap
Definition: OdometryInfo.h:116
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:42
static Transform getIdentity()
Definition: Transform.cpp:364
const cv::Mat & descriptors() const
Definition: SensorData.h:229
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
int maxPoints() const
Definition: LaserScan.h:64
const std::vector< cv::KeyPoint > & keypoints() const
Definition: SensorData.h:227
const std::multimap< int, cv::Mat > & getWordsDescriptors() const
Definition: Signature.h:111
const Transform & getPose() const
Definition: Odometry.h:71
std::vector< int > inliersIDs
Transform lastKeyFramePose_
Definition: OdometryF2F.h:61
const LaserScan & laserScanRaw() const
Definition: SensorData.h:163
int size() const
Definition: LaserScan.h:70
static int findPairsUnique(const std::multimap< int, cv::KeyPoint > &wordsA, const std::multimap< int, cv::KeyPoint > &wordsB, std::list< std::pair< int, std::pair< cv::KeyPoint, cv::KeyPoint > > > &pairs, bool ignoreNegativeIds=true)
cv::Mat rightRaw() const
Definition: SensorData.h:173
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
#define UASSERT(condition)
bool isValid() const
Definition: SensorData.h:134
Wrappers of STL for convenient functions.
bool isNull() const
Definition: Transform.cpp:107
OdometryF2F(const rtabmap::ParametersMap &parameters=rtabmap::ParametersMap())
Definition: OdometryF2F.cpp:39
std::vector< int > cornerInliers
Definition: OdometryInfo.h:122
LaserScan RTABMAP_EXP transformLaserScan(const LaserScan &laserScan, const Transform &transform)
bool isScanRequired() const
virtual void parseParameters(const ParametersMap &parameters)
void setWordsDescriptors(const std::multimap< int, cv::Mat > &descriptors)
Definition: Signature.h:112
Transform localTransform() const
Definition: LaserScan.h:67
ParametersMap parameters_
Definition: OdometryF2F.h:62
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:193
static Registration * create(const ParametersMap &parameters)
#define UDEBUG(...)
std::multimap< int, cv::KeyPoint > words
Definition: OdometryInfo.h:115
SensorData & sensorData()
Definition: Signature.h:134
#define UERROR(...)
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
Definition: SensorData.h:194
#define UWARN(...)
bool isImageRequired() const
std::vector< cv::Point2f > newCorners
Definition: OdometryInfo.h:121
RegistrationInfo reg
Definition: OdometryInfo.h:91
Transform inverse() const
Definition: Transform.cpp:169
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
Definition: OdometryF2F.cpp:69
std::string UTILITE_EXP uNumber2Str(unsigned int number)
Definition: UConversion.cpp:90
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
Definition: SensorData.cpp:828
const std::vector< cv::Point3f > & keypoints3D() const
Definition: SensorData.h:228
cv::Mat depthRaw() const
Definition: SensorData.h:172
Registration * registrationPipeline_
Definition: OdometryF2F.h:59
RegistrationInfo copyWithoutData() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: OdometryF2F.cpp:61
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32