53 #include <pcl/pcl_base.h>
60 int odomTypeInt = Parameters::defaultOdomStrategy();
88 #if defined(RTABMAP_ORB_SLAM) and RTABMAP_ORB_SLAM == 2
116 UERROR(
"Unknown odometry type %d, using F2M instead...", (
int)
type);
125 _resetCountdown(
Parameters::defaultOdomResetCountdown()),
126 _force3DoF(
Parameters::defaultRegForce3DoF()),
127 _holonomic(
Parameters::defaultOdomHolonomic()),
128 guessFromMotion_(
Parameters::defaultOdomGuessMotion()),
129 guessSmoothingDelay_(
Parameters::defaultOdomGuessSmoothingDelay()),
130 _filteringStrategy(
Parameters::defaultOdomFilteringStrategy()),
131 _particleSize(
Parameters::defaultOdomParticleSize()),
132 _particleNoiseT(
Parameters::defaultOdomParticleNoiseT()),
133 _particleLambdaT(
Parameters::defaultOdomParticleLambdaT()),
134 _particleNoiseR(
Parameters::defaultOdomParticleNoiseR()),
135 _particleLambdaR(
Parameters::defaultOdomParticleLambdaR()),
136 _fillInfoData(
Parameters::defaultOdomFillInfoData()),
137 _kalmanProcessNoise(
Parameters::defaultOdomKalmanProcessNoise()),
138 _kalmanMeasurementNoise(
Parameters::defaultOdomKalmanMeasurementNoise()),
139 _imageDecimation(
Parameters::defaultOdomImageDecimation()),
140 _alignWithGround(
Parameters::defaultOdomAlignWithGround()),
141 _publishRAMUsage(
Parameters::defaultRtabmapPublishRAMUsage()),
142 _imagesAlreadyRectified(
Parameters::defaultRtabmapImagesAlreadyRectified()),
143 _deskewing(
Parameters::defaultOdomDeskewing()),
145 _resetCurrentCount(0),
147 distanceTravelled_(0),
232 UWARN(
"Force2D=true and the initial pose contains z, roll or pitch values (%s). They are set to null.", initialPose.
prettyPrint().c_str());
274 if(transforms.size())
276 float tvx=0.0f,tvy=0.0f,tvz=0.0f, tvroll=0.0f,tvpitch=0.0f,tvyaw=0.0f;
277 for(std::list<std::pair<std::vector<float>,
double> >::const_iterator
iter=transforms.begin();
iter!=transforms.end(); ++
iter)
283 tvroll+=
iter->first[3];
284 tvpitch+=
iter->first[4];
285 tvyaw+=
iter->first[5];
287 tvx/=
float(transforms.size());
288 tvy/=
float(transforms.size());
289 tvz/=
float(transforms.size());
290 tvroll/=
float(transforms.size());
291 tvpitch/=
float(transforms.size());
292 tvyaw/=
float(transforms.size());
293 return Transform(tvx, tvy, tvz, tvroll, tvpitch, tvyaw);
308 if(!
data.imu().empty() && !
this->canProcessAsyncIMU())
310 if(!(
data.imu().orientation()[0] == 0.0 &&
data.imu().orientation()[1] == 0.0 &&
data.imu().orientation()[2] == 0.0))
314 Transform imuT =
Transform(
data.imu().localTransform().x(),
data.imu().localTransform().y(),
data.imu().localTransform().z(), 0,0,
data.imu().localTransform().theta()) *
316 data.imu().localTransform().rotation().inverse();
323 Transform newFramePose =
Transform(previous.
x(), previous.
y(), previous.
z(), imuQuat.x(), imuQuat.y(), imuQuat.z(), imuQuat.w());
324 UWARN(
"Updated initial pose from %s to %s with IMU orientation", previous.
prettyPrint().c_str(), newFramePose.
prettyPrint().c_str());
325 this->
reset(newFramePose);
328 imus_.insert(std::make_pair(
data.stamp(), imuT));
329 if(
imus_.size() > 1000)
336 UWARN(
"Received IMU doesn't have orientation set! It is ignored.");
340 if(!
data.imageRaw().empty())
342 UDEBUG(
"Processing image data %dx%d: rgbd models=%ld, stereo models=%ld",
343 data.imageRaw().cols,
344 data.imageRaw().rows,
345 data.cameraModels().size(),
346 data.stereoCameraModels().size());
352 if(!
data.stereoCameraModels().empty())
362 for(
size_t i=0;
i<
data.stereoCameraModels().
size() && valid; ++
i)
380 UWARN(
"%s parameter is set to false but the selected odometry approach cannot "
381 "process raw stereo images. We will rectify them for convenience.",
382 Parameters::kRtabmapImagesAlreadyRectified().
c_str());
386 UERROR(
"Odometry approach chosen cannot process raw stereo images (not rectified images) "
387 "and we cannot rectify them as the rectification map failed to initialize (valid calibration?). "
388 "Make sure images are rectified and set %s parameter back to true, or "
389 "make sure calibration is valid for rectification",
390 Parameters::kRtabmapImagesAlreadyRectified().
c_str());
406 UASSERT(
int((
data.imageRaw().cols/
data.stereoCameraModels().size())*
data.stereoCameraModels().size()) ==
data.imageRaw().cols);
407 int subImageWidth =
data.imageRaw().cols/
data.stereoCameraModels().size();
408 cv::Mat rectifiedLeftImages =
data.imageRaw().clone();
409 cv::Mat rectifiedRightImages =
data.imageRaw().clone();
412 cv::Mat rectifiedLeft =
stereoModels_[
i].left().rectifyImage(cv::Mat(
data.imageRaw(), cv::Rect(subImageWidth*
i, 0, subImageWidth,
data.imageRaw().rows)));
413 cv::Mat rectifiedRight =
stereoModels_[
i].right().rectifyImage(cv::Mat(
data.rightRaw(), cv::Rect(subImageWidth*
i, 0, subImageWidth,
data.rightRaw().rows)));
414 rectifiedLeft.copyTo(cv::Mat(rectifiedLeftImages, cv::Rect(subImageWidth*
i, 0, subImageWidth,
data.imageRaw().rows)));
415 rectifiedRight.copyTo(cv::Mat(rectifiedRightImages, cv::Rect(subImageWidth*
i, 0, subImageWidth,
data.imageRaw().rows)));
417 data.setStereoImage(rectifiedLeftImages, rectifiedRightImages,
stereoModels_,
false);
421 else if(!
data.cameraModels().empty())
431 for(
size_t i=0;
i<
data.cameraModels().
size() && valid; ++
i)
433 valid =
models_[
i].isRectificationMapInitialized() &&
434 models_[
i].imageSize() ==
data.cameraModels()[
i].imageSize();
442 for(
size_t i=0;
i<
models_.size() && valid; ++
i)
444 valid =
models_[
i].initRectificationMap();
448 UWARN(
"%s parameter is set to false but the selected odometry approach cannot "
449 "process raw images. We will rectify them for convenience (only "
450 "rgb is rectified, we assume depth image is already rectified!).",
451 Parameters::kRtabmapImagesAlreadyRectified().
c_str());
455 UERROR(
"Odometry approach chosen cannot process raw images (not rectified images) "
456 "and we cannot rectify them as the rectification map failed to initialize (valid calibration?). "
457 "Make sure images are rectified and set %s parameter back to true, or "
458 "make sure calibration is valid for rectification",
459 Parameters::kRtabmapImagesAlreadyRectified().
c_str());
472 UASSERT(
int((
data.imageRaw().cols/
data.cameraModels().size())*
data.cameraModels().size()) ==
data.imageRaw().cols);
473 int subImageWidth =
data.imageRaw().cols/
data.cameraModels().size();
474 cv::Mat rectifiedImages =
data.imageRaw().clone();
475 for(
size_t i=0;
i<
models_.size() && valid; ++
i)
477 cv::Mat rectifiedImage =
models_[
i].rectifyImage(cv::Mat(
data.imageRaw(), cv::Rect(subImageWidth*
i, 0, subImageWidth,
data.imageRaw().rows)));
478 rectifiedImage.copyTo(cv::Mat(rectifiedImages, cv::Rect(subImageWidth*
i, 0, subImageWidth,
data.imageRaw().rows)));
486 UERROR(
"Odometry approach chosen cannot process raw images (not rectified images). Make sure images "
487 "are rectified, and set %s parameter back to true, or make sure that calibration is valid "
488 "for rectification so we can rectifiy them for convenience",
489 Parameters::kRtabmapImagesAlreadyRectified().
c_str());
496 if(
data.depthOrRightRaw().empty())
498 UWARN(
"\"%s\" is true but the input has no depth information, ignoring alignment with ground...", Parameters::kOdomAlignWithGround().
c_str());
503 pcl::IndicesPtr
indices(
new std::vector<int>);
504 pcl::IndicesPtr ground, obstacles;
506 bool success =
false;
515 util3d::segmentObstaclesFromGround<pcl::PointXYZ>(cloud, ground, obstacles, 20,
M_PI/4.0
f, 0.02, 200,
true);
518 pcl::ModelCoefficients coefficients;
520 if(coefficients.values.at(3) >= 0)
522 UWARN(
"Ground detected! coefficients=(%f, %f, %f, %f) time=%fs",
523 coefficients.values.at(0),
524 coefficients.values.at(1),
525 coefficients.values.at(2),
526 coefficients.values.at(3),
531 UWARN(
"Ceiling detected! coefficients=(%f, %f, %f, %f) time=%fs",
532 coefficients.values.at(0),
533 coefficients.values.at(1),
534 coefficients.values.at(2),
535 coefficients.values.at(3),
538 Eigen::Vector3f
n(coefficients.values.at(0), coefficients.values.at(1), coefficients.values.at(2));
539 Eigen::Vector3f
z(0,0,1);
546 R(0,0),
R(0,1),
R(0,2), 0,
547 R(1,0),
R(1,1),
R(1,2), 0,
548 R(2,0),
R(2,1),
R(2,2), coefficients.values.at(3));
549 this->
reset(rotation);
554 UWARN(
"Rotation was already initialized, just offseting z to %f", coefficients.values.at(3));
556 pose.
z() = coefficients.values.at(3);
564 UERROR(
"Odometry failed to detect the ground. You have this "
565 "error because parameter \"%s\" is true. "
566 "Make sure the camera is seeing the ground (e.g., tilt ~30 "
567 "degrees toward the ground).", Parameters::kOdomAlignWithGround().
c_str());
579 UERROR(
"Guess from motion is set but dt is invalid! Odometry is then computed without guess. (dt=%f previous transform=%s)",
dt,
velocityGuess_.
prettyPrint().c_str());
583 UERROR(
"Kalman filtering is enabled but dt is invalid! Odometry is then computed without Kalman filtering. (dt=%f previous transform=%s)",
dt,
velocityGuess_.
prettyPrint().c_str());
596 float vx,
vy,vz, vroll,vpitch,vyaw;
602 float vx,
vy,vz, vroll,vpitch,vyaw;
618 else if(!
imus_.empty())
636 UWARN(
"Could not find imu transform at %f",
data.stamp());
644 !
data.laserScanRaw().empty() &&
645 data.laserScanRaw().hasTime() &&
649 UDEBUG(
"Deskewing begin");
651 float vx,
vy,vz, vroll,vpitch,vyaw;
665 data.laserScanRaw().data().ptr<
float>(0,
data.laserScanRaw().size()-1)[
data.laserScanRaw().getTimeOffset()] -
666 data.laserScanRaw().data().ptr<
float>(0, 0)[
data.laserScanRaw().getTimeOffset()];
671 data.laserScanRaw().data().ptr<
float>(0, 0)[
data.laserScanRaw().getTimeOffset()]);
674 data.laserScanRaw().data().ptr<
float>(0,
data.laserScanRaw().size()-1)[
data.laserScanRaw().getTimeOffset()]);
698 data.setLaserScan(scanDeskewed);
703 if(
data.laserScanRaw().isOrganized())
706 data.setLaserScan(
data.laserScanRaw().densify());
716 if( !
data.cameraModels().empty() &&
717 data.cameraModels()[0].imageHeight()>0 &&
718 data.cameraModels()[0].imageWidth()>0)
722 if(targetSize >=
data.depthRaw().rows)
728 decimationDepth = (
int)
ceil(
float(
data.depthRaw().rows) /
float(targetSize));
731 UDEBUG(
"decimation rgbOrLeft(rows=%d)=%d, depthOrRight(rows=%d)=%d",
data.imageRaw().rows,
_imageDecimation,
data.depthOrRightRaw().rows, decimationDepth);
735 std::vector<CameraModel> cameraModels = decimatedData.
cameraModels();
736 for(
unsigned int i=0;
i<cameraModels.size(); ++
i)
740 if(!cameraModels.empty())
742 decimatedData.
setRGBDImage(rgbLeft, depthRight, cameraModels);
747 for(
unsigned int i=0;
i<stereoModels.size(); ++
i)
751 if(!stereoModels.empty())
762 std::vector<cv::KeyPoint> kpts = decimatedData.
keypoints();
764 for(
unsigned int i=0;
i<kpts.size(); ++
i)
769 kpts[
i].octave += log2value;
777 for(
unsigned int i=0;
i<
info->newCorners.size(); ++
i)
781 if(!
info->refCorners.empty())
787 for(std::multimap<int, cv::KeyPoint>::iterator
iter=
info->words.begin();
iter!=
info->words.end(); ++
iter)
792 iter->second.octave += log2value;
796 else if(!
data.imageRaw().empty() || !
data.laserScanRaw().isEmpty() || (
this->canProcessAsyncIMU() && !
data.imu().empty()))
801 if(
data.imageRaw().empty() &&
data.laserScanRaw().isEmpty() && !
data.imu().empty())
808 info->timeEstimation =
time.ticks();
809 info->lost =
t.isNull();
819 if(!
data.groundTruth().isNull())
833 float vx,
vy,vz, vroll,vpitch,vyaw;
834 t.getTranslationAndEulerAngles(
vx,
vy,vz, vroll,vpitch,vyaw);
893 float tmpY = vyaw!=0.0f ?
vx /
tan((CV_PI-vyaw)/2.0
f) : 0.0f;
894 if(
fabs(tmpY) <
fabs(
vy) || (tmpY<=0 && vy >=0) || (tmpY>=0 &&
vy<=0))
914 info->timeParticleFiltering =
time.ticks();
920 vy = vyaw!=0.0f ?
vx /
tan((CV_PI-vyaw)/2.0
f) : 0.0f;
942 info->transformFiltered =
t;
948 UWARN(
"Null stamp detected");
963 std::vector<float>
v(6);
998 UWARN(
"Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...",
_resetCurrentCount);
1003 UWARN(
"Odometry automatically reset to latest pose!");
1029 int nMeasurements = 6;
1186 *
vx = prediction.at<
float>(3);
1188 *
vy = prediction.at<
float>(4);
1190 *vz =
_force3DoF?0.0f:prediction.at<
float>(5);
1192 *vroll =
_force3DoF?0.0f:prediction.at<
float>(12);
1194 *vpitch =
_force3DoF?0.0f:prediction.at<
float>(13);
1196 *vyaw = prediction.at<
float>(
_force3DoF?7:14);
1202 cv::Mat measurements;
1205 measurements = cv::Mat(6,1,CV_32FC1);
1206 measurements.at<
float>(0) =
vx;
1207 measurements.at<
float>(1) =
vy;
1208 measurements.at<
float>(2) = vz;
1209 measurements.at<
float>(3) = vroll;
1210 measurements.at<
float>(4) = vpitch;
1211 measurements.at<
float>(5) = vyaw;
1215 measurements = cv::Mat(3,1,CV_32FC1);
1216 measurements.at<
float>(0) =
vx;
1217 measurements.at<
float>(1) =
vy;
1218 measurements.at<
float>(2) = vyaw;
1223 const cv::Mat & estimated =
kalmanFilter_.correct(measurements);
1226 vx = estimated.at<
float>(3);
1227 vy = estimated.at<
float>(4);
1229 vroll =
_force3DoF?0.0f:estimated.at<
float>(12);
1230 vpitch =
_force3DoF?0.0f:estimated.at<
float>(13);