OdometryInfo.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2025, 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 
30 
31 namespace rtabmap {
32 
34  lost(true),
35  features(0),
36  localMapSize(0),
37  localScanMapSize(0),
38  localKeyFrames(0),
39  localBundleOutliers(0),
40  localBundleConstraints(0),
41  localBundleTime(0),
42  localBundleAvgInlierDistance(0.0f),
43  localBundleMaxKeyFramesForInlier(0),
44  keyFrameAdded(false),
45  timeDeskewing(0.0f),
46  timeEstimation(0.0f),
47  timeParticleFiltering(0.0f),
48  stamp(0),
49  interval(0),
50  distanceTravelled(0.0f),
51  memoryUsage(0),
52  gravityRollError(0.0),
53  gravityPitchError(0.0),
54  type(0)
55 {}
56 
58 {
59  OdometryInfo output;
60  output.lost = lost;
61  output.reg = reg.copyWithoutData();
62  output.features = features;
63  output.localMapSize = localMapSize;
78  output.stamp = stamp;
79  output.interval = interval;
80  output.transform = transform;
84  output.guess = guess;
86  output.memoryUsage = memoryUsage;
89  output.type = type;
90  return output;
91 }
92 
93 std::map<std::string, float> OdometryInfo::statistics(const Transform & pose)
94 {
95  std::map<std::string, float> stats;
96 
97  stats.insert(std::make_pair("Odometry/TimeRegistration/ms", reg.totalTime*1000.0f));
98  stats.insert(std::make_pair("Odometry/RAM_usage/MB", memoryUsage));
99 
100  // Based on rtabmap/MainWindow.cpp
101  stats.insert(std::make_pair("Odometry/Features/", features));
102  stats.insert(std::make_pair("Odometry/Matches/", reg.matches));
103  stats.insert(std::make_pair("Odometry/MatchesRatio/", features<=0?0.0f:float(reg.inliers)/float(features)));
104  stats.insert(std::make_pair("Odometry/Inliers/", reg.inliers));
105  stats.insert(std::make_pair("Odometry/InliersMeanDistance/m", reg.inliersMeanDistance));
106  stats.insert(std::make_pair("Odometry/InliersDistribution/", reg.inliersDistribution));
107  stats.insert(std::make_pair("Odometry/InliersRatio/", reg.inliers));
108  for(size_t i=0; i<reg.matchesPerCam.size(); ++i)
109  {
110  stats.insert(std::make_pair(uFormat("Odometry/matchesCam%ld/", i), reg.matchesPerCam[i]));
111  }
112  for(size_t i=0; i<reg.inliersPerCam.size(); ++i)
113  {
114  stats.insert(std::make_pair(uFormat("Odometry/inliersCam%ld/", i), reg.inliersPerCam[i]));
115  }
116  if(reg.matchesPerCam.size() == reg.inliersPerCam.size())
117  {
118  for(size_t i=0; i<reg.matchesPerCam.size(); ++i)
119  {
120  stats.insert(std::make_pair(uFormat("Odometry/inliersRatioCam%ld/", i), reg.matchesPerCam[i]>0 ? (float)reg.inliersPerCam[i] / (float)reg.matchesPerCam[i] : 0.0f));
121  }
122  }
123  stats.insert(std::make_pair("Odometry/ICPInliersRatio/", reg.icpInliersRatio));
124  stats.insert(std::make_pair("Odometry/ICPRotation/rad", reg.icpRotation));
125  stats.insert(std::make_pair("Odometry/ICPTranslation/m", reg.icpTranslation));
126  stats.insert(std::make_pair("Odometry/ICPStructuralComplexity/", reg.icpStructuralComplexity));
127  stats.insert(std::make_pair("Odometry/ICPStructuralDistribution/", reg.icpStructuralDistribution));
128  stats.insert(std::make_pair("Odometry/ICPCorrespondences/", reg.icpCorrespondences));
129  stats.insert(std::make_pair("Odometry/StdDevLin/", sqrt((float)reg.covariance.at<double>(0,0))));
130  stats.insert(std::make_pair("Odometry/StdDevAng/", sqrt((float)reg.covariance.at<double>(5,5))));
131  stats.insert(std::make_pair("Odometry/VarianceLin/", (float)reg.covariance.at<double>(0,0)));
132  stats.insert(std::make_pair("Odometry/VarianceAng/", (float)reg.covariance.at<double>(5,5)));
133  stats.insert(std::make_pair("Odometry/TimeEstimation/ms", timeEstimation*1000.0f));
134  stats.insert(std::make_pair("Odometry/TimeFiltering/ms", timeParticleFiltering*1000.0f));
135  stats.insert(std::make_pair("Odometry/LocalMapSize/", localMapSize));
136  stats.insert(std::make_pair("Odometry/LocalScanMapSize/", localScanMapSize));
137  stats.insert(std::make_pair("Odometry/LocalKeyFrames/", localKeyFrames));
138  stats.insert(std::make_pair("Odometry/LocalBundleOutliers/", localBundleOutliers));
139  stats.insert(std::make_pair("Odometry/LocalBundleConstraints/", localBundleConstraints));
140  stats.insert(std::make_pair("Odometry/LocalBundleTime/ms", localBundleTime*1000.0f));
141  stats.insert(std::make_pair("Odometry/localBundleAvgInlierDistance/pix", localBundleAvgInlierDistance));
142  stats.insert(std::make_pair("Odometry/localBundleMaxKeyFramesForInlier/", localBundleMaxKeyFramesForInlier));
143  for(size_t i=0; i<localBundleOutliersPerCam.size(); ++i)
144  {
145  stats.insert(std::make_pair(uFormat("Odometry/localBundleOutliersCam%ld/", i), localBundleOutliersPerCam[i]));
146  }
147  stats.insert(std::make_pair("Odometry/KeyFrameAdded/", keyFrameAdded?1.0f:0.0f));
148  stats.insert(std::make_pair("Odometry/Interval/ms", (float)interval));
149  stats.insert(std::make_pair("Odometry/Distance/m", distanceTravelled));
150 
151  float x,y,z,roll,pitch,yaw;
152  if(!pose.isNull())
153  {
155  stats.insert(std::make_pair("Odometry/Px/m", x));
156  stats.insert(std::make_pair("Odometry/Py/m", y));
157  stats.insert(std::make_pair("Odometry/Pz/m", z));
158  stats.insert(std::make_pair("Odometry/Proll/deg", roll*180.0/CV_PI));
159  stats.insert(std::make_pair("Odometry/Ppitch/deg", pitch*180.0/CV_PI));
160  stats.insert(std::make_pair("Odometry/Pyaw/deg", yaw*180.0/CV_PI));
161  }
162 
163  float dist = 0.0f, speed=0.0f;
164  if(!transform.isNull())
165  {
167  dist = transform.getNorm();
168  stats.insert(std::make_pair("Odometry/T/m", dist));
169  stats.insert(std::make_pair("Odometry/Tx/m", x));
170  stats.insert(std::make_pair("Odometry/Ty/m", y));
171  stats.insert(std::make_pair("Odometry/Tz/m", z));
172  stats.insert(std::make_pair("Odometry/Troll/deg", roll*180.0/CV_PI));
173  stats.insert(std::make_pair("Odometry/Tpitch/deg", pitch*180.0/CV_PI));
174  stats.insert(std::make_pair("Odometry/Tyaw/deg", yaw*180.0/CV_PI));
175 
176  if(interval>0.0)
177  {
178  speed = dist/interval;
179  stats.insert(std::make_pair("Odometry/Speed/kph", speed*3.6));
180  stats.insert(std::make_pair("Odometry/Speed/mph", speed*2.237));
181  stats.insert(std::make_pair("Odometry/Speed/mps", speed));
182  stats.insert(std::make_pair("Odometry/Vx/mps", x/interval));
183  stats.insert(std::make_pair("Odometry/Vy/mps", y/interval));
184  stats.insert(std::make_pair("Odometry/Vz/mps", z/interval));
185  stats.insert(std::make_pair("Odometry/Vroll/degps", (roll*180.0/CV_PI)/interval));
186  stats.insert(std::make_pair("Odometry/Vpitch/degps", (pitch*180.0/CV_PI)/interval));
187  stats.insert(std::make_pair("Odometry/Vyaw/degps", (yaw*180.0/CV_PI)/interval));
188  }
189  }
191  {
192  if(!transform.isNull())
193  {
195  stats.insert(std::make_pair("Odometry/TG_error_lin/m", diff.getNorm()));
196  stats.insert(std::make_pair("Odometry/TG_error_ang/deg", diff.getAngle()*180.0/CV_PI));
197  }
198 
201  stats.insert(std::make_pair("Odometry/TG/m", dist));
202  stats.insert(std::make_pair("Odometry/TGx/m", x));
203  stats.insert(std::make_pair("Odometry/TGy/m", y));
204  stats.insert(std::make_pair("Odometry/TGz/m", z));
205  stats.insert(std::make_pair("Odometry/TGroll/deg", roll*180.0/CV_PI));
206  stats.insert(std::make_pair("Odometry/TGpitch/deg", pitch*180.0/CV_PI));
207  stats.insert(std::make_pair("Odometry/TGyaw/deg", yaw*180.0/CV_PI));
208 
209  if(interval>0.0)
210  {
211  speed = dist/interval;
212  stats.insert(std::make_pair("Odometry/SpeedG/kph", speed*3.6));
213  stats.insert(std::make_pair("Odometry/SpeedG/mph", speed*2.237));
214  stats.insert(std::make_pair("Odometry/SpeedG/mps", speed));
215  }
216  }
217  return stats;
218 }
219 
220 } // namespace rtabmap
rtabmap::OdometryInfo::localMapSize
int localMapSize
Definition: OdometryInfo.h:51
rtabmap::RegistrationInfo::icpStructuralComplexity
float icpStructuralComplexity
Definition: RegistrationInfo.h:97
glm::yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
OdometryInfo.h
rtabmap::OdometryInfo::timeParticleFiltering
float timeParticleFiltering
Definition: OdometryInfo.h:65
rtabmap::RegistrationInfo::matchesPerCam
std::vector< int > matchesPerCam
Definition: RegistrationInfo.h:91
rtabmap::OdometryInfo::localBundleTime
float localBundleTime
Definition: OdometryInfo.h:56
rtabmap::OdometryInfo::keyFrameAdded
bool keyFrameAdded
Definition: OdometryInfo.h:62
rtabmap::OdometryInfo::timeEstimation
float timeEstimation
Definition: OdometryInfo.h:64
rtabmap::Transform::getNorm
float getNorm() const
Definition: Transform.cpp:283
rtabmap::OdometryInfo::features
int features
Definition: OdometryInfo.h:50
rtabmap::OdometryInfo::lost
bool lost
Definition: OdometryInfo.h:48
rtabmap::RegistrationInfo::inliersDistribution
float inliersDistribution
Definition: RegistrationInfo.h:85
rtabmap::OdometryInfo::transformFiltered
Transform transformFiltered
Definition: OdometryInfo.h:69
rtabmap::RegistrationInfo::icpCorrespondences
int icpCorrespondences
Definition: RegistrationInfo.h:99
rtabmap::RegistrationInfo::inliersMeanDistance
float inliersMeanDistance
Definition: RegistrationInfo.h:84
type
y
Matrix3f y
true
#define true
Definition: ConvertUTF.c:57
rtabmap::OdometryInfo::localKeyFrames
int localKeyFrames
Definition: OdometryInfo.h:53
rtabmap::Transform::isNull
bool isNull() const
Definition: Transform.cpp:107
rtabmap::RegistrationInfo::copyWithoutData
RegistrationInfo copyWithoutData() const
Definition: RegistrationInfo.h:55
rtabmap::OdometryInfo::transform
Transform transform
Definition: OdometryInfo.h:68
rtabmap::OdometryInfo::statistics
std::map< std::string, float > statistics(const Transform &pose=Transform())
Definition: OdometryInfo.cpp:93
rtabmap::Transform::getTranslationAndEulerAngles
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:258
rtabmap::RegistrationInfo::inliersPerCam
std::vector< int > inliersPerCam
Definition: RegistrationInfo.h:90
rtabmap::OdometryInfo::localBundleModels
std::map< int, std::vector< CameraModel > > localBundleModels
Definition: OdometryInfo.h:58
rtabmap::OdometryInfo::type
int type
Definition: OdometryInfo.h:78
rtabmap::OdometryInfo::localBundleMaxKeyFramesForInlier
int localBundleMaxKeyFramesForInlier
Definition: OdometryInfo.h:60
rtabmap::OdometryInfo::localBundlePoses
std::map< int, Transform > localBundlePoses
Definition: OdometryInfo.h:57
stats
bool stats
UConversion.h
Some conversion functions.
glm::sqrt
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
rtabmap::OdometryInfo::localBundleOutliersPerCam
std::vector< int > localBundleOutliersPerCam
Definition: OdometryInfo.h:61
rtabmap::OdometryInfo::localBundleConstraints
int localBundleConstraints
Definition: OdometryInfo.h:55
rtabmap::OdometryInfo::guessVelocity
Transform guessVelocity
Definition: OdometryInfo.h:71
rtabmap::OdometryInfo::localScanMapSize
int localScanMapSize
Definition: OdometryInfo.h:52
rtabmap::RegistrationInfo::covariance
cv::Mat covariance
Definition: RegistrationInfo.h:77
rtabmap::RegistrationInfo::icpInliersRatio
float icpInliersRatio
Definition: RegistrationInfo.h:94
rtabmap::RegistrationInfo::inliers
int inliers
Definition: RegistrationInfo.h:82
z
z
x
x
rtabmap::OdometryInfo::copyWithoutData
OdometryInfo copyWithoutData() const
Definition: OdometryInfo.cpp:57
rtabmap::RegistrationInfo::icpTranslation
float icpTranslation
Definition: RegistrationInfo.h:95
glm::pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap::Transform::inverse
Transform inverse() const
Definition: Transform.cpp:178
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
rtabmap::OdometryInfo::stamp
double stamp
Definition: OdometryInfo.h:66
rtabmap::RegistrationInfo::matches
int matches
Definition: RegistrationInfo.h:87
rtabmap::RegistrationInfo::totalTime
double totalTime
Definition: RegistrationInfo.h:79
rtabmap::Transform
Definition: Transform.h:41
rtabmap::OdometryInfo::OdometryInfo
OdometryInfo()
Definition: OdometryInfo.cpp:33
rtabmap::OdometryInfo::distanceTravelled
float distanceTravelled
Definition: OdometryInfo.h:73
rtabmap::RegistrationInfo::icpRotation
float icpRotation
Definition: RegistrationInfo.h:96
rtabmap::OdometryInfo::gravityPitchError
double gravityPitchError
Definition: OdometryInfo.h:76
diff
diff
rtabmap::OdometryInfo::interval
double interval
Definition: OdometryInfo.h:67
rtabmap::OdometryInfo::reg
RegistrationInfo reg
Definition: OdometryInfo.h:49
rtabmap::OdometryInfo
Definition: OdometryInfo.h:41
rtabmap::OdometryInfo::memoryUsage
int memoryUsage
Definition: OdometryInfo.h:74
rtabmap::OdometryInfo::timeDeskewing
float timeDeskewing
Definition: OdometryInfo.h:63
false
#define false
Definition: ConvertUTF.c:56
rtabmap::OdometryInfo::guess
Transform guess
Definition: OdometryInfo.h:72
dist
dist
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::OdometryInfo::transformGroundTruth
Transform transformGroundTruth
Definition: OdometryInfo.h:70
rtabmap::OdometryInfo::gravityRollError
double gravityRollError
Definition: OdometryInfo.h:75
rtabmap::OdometryInfo::localBundleAvgInlierDistance
float localBundleAvgInlierDistance
Definition: OdometryInfo.h:59
i
int i
glm::roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
rtabmap::OdometryInfo::localBundleOutliers
int localBundleOutliers
Definition: OdometryInfo.h:54
rtabmap::RegistrationInfo::icpStructuralDistribution
float icpStructuralDistribution
Definition: RegistrationInfo.h:98


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:57