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.removeAllWords();
141  UWARN("Failed to find a transformation with the provided guess (%s), trying again without a guess.", guess.prettyPrint().c_str());
142  // If optical flow is used, switch temporary to feature matching
143  int visCorTypeBackup = Parameters::defaultVisCorType();
144  Parameters::parse(parameters_, Parameters::kVisCorType(), visCorTypeBackup);
145  if(visCorTypeBackup == 1)
146  {
147  ParametersMap params;
148  params.insert(ParametersPair(Parameters::kVisCorType(), "0"));
150  }
151 
153  tmpRefFrame,
154  newFrame,
155  Transform(), // null guess
156  &regInfo);
157 
158  if(visCorTypeBackup == 1)
159  {
160  ParametersMap params;
161  params.insert(ParametersPair(Parameters::kVisCorType(), "1"));
163  }
164 
165  if(output.isNull())
166  {
167  UWARN("Trial with no guess still fail.");
168  }
169  else
170  {
171  UWARN("Trial with no guess succeeded.");
172  }
173  }
174 
175  if(info && this->isInfoDataFilled())
176  {
177  std::list<std::pair<int, std::pair<int, int> > > pairs;
178  EpipolarGeometry::findPairsUnique(tmpRefFrame.getWords(), newFrame.getWords(), pairs);
179  info->refCorners.resize(pairs.size());
180  info->newCorners.resize(pairs.size());
181  std::map<int, int> idToIndex;
182  int i=0;
183  for(std::list<std::pair<int, std::pair<int, int> > >::iterator iter=pairs.begin();
184  iter!=pairs.end();
185  ++iter)
186  {
187  info->refCorners[i] = tmpRefFrame.getWordsKpts()[iter->second.first].pt;
188  info->newCorners[i] = newFrame.getWordsKpts()[iter->second.second].pt;
189  idToIndex.insert(std::make_pair(iter->first, i));
190  ++i;
191  }
192  info->cornerInliers.resize(regInfo.inliersIDs.size(), 1);
193  i=0;
194  for(; i<(int)regInfo.inliersIDs.size(); ++i)
195  {
196  info->cornerInliers[i] = idToIndex.at(regInfo.inliersIDs[i]);
197  }
198 
199  Transform t = this->getPose()*motionSinceLastKeyFrame.inverse();
200  if(!tmpRefFrame.getWords3().empty())
201  {
202  for(std::multimap<int, int>::const_iterator iter=tmpRefFrame.getWords().begin(); iter!=tmpRefFrame.getWords().end(); ++iter)
203  {
204  info->localMap.insert(std::make_pair(iter->first, util3d::transformPoint(tmpRefFrame.getWords3()[iter->second], t)));
205  }
206  }
207  info->localMapSize = tmpRefFrame.getWords3().size();
208  if(!newFrame.getWordsKpts().empty())
209  {
210  for(std::multimap<int, int>::const_iterator iter=newFrame.getWords().begin(); iter!=newFrame.getWords().end(); ++iter)
211  {
212  info->words.insert(std::make_pair(iter->first, newFrame.getWordsKpts()[iter->second]));
213  }
214  }
215 
216  info->localScanMapSize = tmpRefFrame.sensorData().laserScanRaw().size();
217 
219  }
220  }
221  else
222  {
223  //return Identity
224  output = Transform::getIdentity();
225  // a very high variance tells that the new pose is not linked with the previous one
226  regInfo.covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0;
227  }
228 
229  if(!output.isNull())
230  {
231  output = motionSinceLastKeyFrame.inverse() * output;
232 
233  // new key-frame?
235  (keyFrameThr_ == 0.0f ||
236  visKeyFrameThr_ == 0 ||
237  float(regInfo.inliers) <= keyFrameThr_*float(refFrame_.sensorData().keypoints().size()) ||
238  regInfo.inliers <= visKeyFrameThr_)) ||
240  {
241  UDEBUG("Update key frame");
242  int features = newFrame.getWordsDescriptors().rows;
243  if(registrationPipeline_->isImageRequired() && features == 0)
244  {
245  newFrame = Signature(data);
246  // this will generate features only for the first frame or if optical flow was used (no 3d words)
247  Signature dummy;
249  newFrame,
250  dummy);
251  features = (int)newFrame.sensorData().keypoints().size();
252  }
253 
256  (newFrame.sensorData().laserScanRaw().size() &&
258  {
259  refFrame_ = newFrame;
260 
262 
263  //reset motion
265 
266  addKeyFrame = true;
267  }
268  else
269  {
270  if (!refFrame_.sensorData().isValid())
271  {
272  // Don't send odometry if we don't have a keyframe yet
273  output.setNull();
274  }
275 
276  if(features < registrationPipeline_->getMinVisualCorrespondences())
277  {
278  UWARN("Too low 2D features (%d), keeping last key frame...", features);
279  }
280 
282  {
283  UWARN("Too low scan points (%d), keeping last key frame...", newFrame.sensorData().laserScanRaw().size());
284  }
286  {
287  UWARN("Too low scan points ratio (%d < %d), keeping last key frame...", float(newFrame.sensorData().laserScanRaw().size())/float(newFrame.sensorData().laserScanRaw().maxPoints()), registrationPipeline_->getMinGeometryCorrespondencesRatio());
288  }
289  }
290  }
291  }
292  else if(!regInfo.rejectedMsg.empty())
293  {
294  UWARN("Registration failed: \"%s\"", regInfo.rejectedMsg.c_str());
295  }
296 
297  data.setFeatures(newFrame.sensorData().keypoints(), newFrame.sensorData().keypoints3D(), newFrame.sensorData().descriptors());
298 
299  if(info)
300  {
301  info->type = kTypeF2F;
302  info->features = newFrame.sensorData().keypoints().size();
303  info->keyFrameAdded = addKeyFrame;
304  if(this->isInfoDataFilled())
305  {
306  info->reg = regInfo;
307  }
308  else
309  {
310  info->reg = regInfo.copyWithoutData();
311  }
312  }
313 
314  UINFO("Odom update time = %fs lost=%s inliers=%d, ref frame corners=%d, transform accepted=%s",
315  timer.elapsed(),
316  output.isNull()?"true":"false",
317  (int)regInfo.inliers,
318  (int)newFrame.sensorData().keypoints().size(),
319  !output.isNull()?"true":"false");
320 
321  return output;
322 }
323 
324 } // namespace rtabmap
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:476
int getMinVisualCorrespondences() const
std::vector< cv::Point2f > refCorners
Definition: OdometryInfo.h:128
unsigned int framesProcessed() const
Definition: Odometry.h:78
Definition: UTimer.h:46
std::string prettyPrint() const
Definition: Transform.cpp:295
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
float getMinGeometryCorrespondencesRatio() const
double elapsed()
Definition: UTimer.h:75
f
bool isInfoDataFilled() const
Definition: Odometry.h:74
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:191
Transform computeTransformationMod(Signature &from, Signature &to, Transform guess=Transform::getIdentity(), RegistrationInfo *info=0) const
std::map< int, cv::Point3f > localMap
Definition: OdometryInfo.h:124
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
static Transform getIdentity()
Definition: Transform.cpp:380
const cv::Mat & descriptors() const
Definition: SensorData.h:251
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
int maxPoints() const
Definition: LaserScan.h:92
const std::vector< cv::KeyPoint > & keypoints() const
Definition: SensorData.h:249
const Transform & getPose() const
Definition: Odometry.h:73
std::vector< int > inliersIDs
Transform lastKeyFramePose_
Definition: OdometryF2F.h:61
const LaserScan & laserScanRaw() const
Definition: SensorData.h:166
int size() const
Definition: LaserScan.h:102
const std::vector< cv::KeyPoint > & getWordsKpts() const
Definition: Signature.h:112
cv::Mat rightRaw() const
Definition: SensorData.h:190
GLM_FUNC_DECL bool isNull(detail::tmat2x2< T, P > const &m, T const &epsilon)
#define UASSERT(condition)
bool isValid() const
Definition: SensorData.h:137
Wrappers of STL for convenient functions.
const std::multimap< int, int > & getWords() const
Definition: Signature.h:111
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:130
LaserScan RTABMAP_EXP transformLaserScan(const LaserScan &laserScan, const Transform &transform)
bool isScanRequired() const
virtual void parseParameters(const ParametersMap &parameters)
const cv::Mat & getWordsDescriptors() const
Definition: Signature.h:115
Transform localTransform() const
Definition: LaserScan.h:98
ParametersMap parameters_
Definition: OdometryF2F.h:62
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:215
static Registration * create(const ParametersMap &parameters)
const std::vector< cv::Point3f > & getWords3() const
Definition: Signature.h:131
#define UDEBUG(...)
std::multimap< int, cv::KeyPoint > words
Definition: OdometryInfo.h:123
SensorData & sensorData()
Definition: Signature.h:137
static int findPairsUnique(const std::multimap< int, T > &wordsA, const std::multimap< int, T > &wordsB, std::list< std::pair< int, std::pair< T, T > > > &pairs, bool ignoreNegativeIds=true)
#define UERROR(...)
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
Definition: SensorData.h:216
#define UWARN(...)
bool isImageRequired() const
std::vector< cv::Point2f > newCorners
Definition: OdometryInfo.h:129
RegistrationInfo reg
Definition: OdometryInfo.h:96
Transform inverse() const
Definition: Transform.cpp:178
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:757
const std::vector< cv::Point3f > & keypoints3D() const
Definition: SensorData.h:250
cv::Mat depthRaw() const
Definition: SensorData.h:189
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 Mon Dec 14 2020 03:34:59