Odometry.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <rtabmap/core/OdometryF2M.h>
00029 #include "rtabmap/core/Odometry.h"
00030 #include "rtabmap/core/OdometryF2F.h"
00031 #include "rtabmap/core/OdometryFovis.h"
00032 #include "rtabmap/core/OdometryViso2.h"
00033 #include "rtabmap/core/OdometryDVO.h"
00034 #include "rtabmap/core/OdometryOkvis.h"
00035 #include "rtabmap/core/OdometryORBSLAM2.h"
00036 #include "rtabmap/core/OdometryLOAM.h"
00037 #include "rtabmap/core/OdometryMSCKF.h"
00038 #include "rtabmap/core/OdometryInfo.h"
00039 #include "rtabmap/core/util3d.h"
00040 #include "rtabmap/core/util3d_mapping.h"
00041 #include "rtabmap/core/util3d_filtering.h"
00042 #include "rtabmap/utilite/ULogger.h"
00043 #include "rtabmap/utilite/UTimer.h"
00044 #include "rtabmap/utilite/UConversion.h"
00045 #include "rtabmap/utilite/UProcessInfo.h"
00046 #include "rtabmap/core/ParticleFilter.h"
00047 #include "rtabmap/core/util2d.h"
00048 
00049 #include <pcl/pcl_base.h>
00050 
00051 namespace rtabmap {
00052 
00053 Odometry * Odometry::create(const ParametersMap & parameters)
00054 {
00055         int odomTypeInt = Parameters::defaultOdomStrategy();
00056         Parameters::parse(parameters, Parameters::kOdomStrategy(), odomTypeInt);
00057         Odometry::Type type = (Odometry::Type)odomTypeInt;
00058         return create(type, parameters);
00059 }
00060 
00061 Odometry * Odometry::create(Odometry::Type & type, const ParametersMap & parameters)
00062 {
00063         UDEBUG("type=%d", (int)type);
00064         Odometry * odometry = 0;
00065         switch(type)
00066         {
00067         case Odometry::kTypeORBSLAM2:
00068                 odometry = new OdometryORBSLAM2(parameters);
00069                 break;
00070         case Odometry::kTypeDVO:
00071                 odometry = new OdometryDVO(parameters);
00072                 break;
00073         case Odometry::kTypeViso2:
00074                 odometry = new OdometryViso2(parameters);
00075                 break;
00076         case Odometry::kTypeFovis:
00077                 odometry = new OdometryFovis(parameters);
00078                 break;
00079         case Odometry::kTypeF2F:
00080                 odometry = new OdometryF2F(parameters);
00081                 break;
00082         case Odometry::kTypeOkvis:
00083                 odometry = new OdometryOkvis(parameters);
00084                 break;
00085         case Odometry::kTypeLOAM:
00086                 odometry = new OdometryLOAM(parameters);
00087                 break;
00088         case Odometry::kTypeMSCKF:
00089                 odometry = new OdometryMSCKF(parameters);
00090                 break;
00091         default:
00092                 odometry = new OdometryF2M(parameters);
00093                 type = Odometry::kTypeF2M;
00094                 break;
00095         }
00096         return odometry;
00097 }
00098 
00099 Odometry::Odometry(const rtabmap::ParametersMap & parameters) :
00100                 _resetCountdown(Parameters::defaultOdomResetCountdown()),
00101                 _force3DoF(Parameters::defaultRegForce3DoF()),
00102                 _holonomic(Parameters::defaultOdomHolonomic()),
00103                 guessFromMotion_(Parameters::defaultOdomGuessMotion()),
00104                 _filteringStrategy(Parameters::defaultOdomFilteringStrategy()),
00105                 _particleSize(Parameters::defaultOdomParticleSize()),
00106                 _particleNoiseT(Parameters::defaultOdomParticleNoiseT()),
00107                 _particleLambdaT(Parameters::defaultOdomParticleLambdaT()),
00108                 _particleNoiseR(Parameters::defaultOdomParticleNoiseR()),
00109                 _particleLambdaR(Parameters::defaultOdomParticleLambdaR()),
00110                 _fillInfoData(Parameters::defaultOdomFillInfoData()),
00111                 _kalmanProcessNoise(Parameters::defaultOdomKalmanProcessNoise()),
00112                 _kalmanMeasurementNoise(Parameters::defaultOdomKalmanMeasurementNoise()),
00113                 _imageDecimation(Parameters::defaultOdomImageDecimation()),
00114                 _alignWithGround(Parameters::defaultOdomAlignWithGround()),
00115                 _publishRAMUsage(Parameters::defaultRtabmapPublishRAMUsage()),
00116                 _imagesAlreadyRectified(Parameters::defaultRtabmapImagesAlreadyRectified()),
00117                 _pose(Transform::getIdentity()),
00118                 _resetCurrentCount(0),
00119                 previousStamp_(0),
00120                 distanceTravelled_(0),
00121                 framesProcessed_(0)
00122 {
00123         Parameters::parse(parameters, Parameters::kOdomResetCountdown(), _resetCountdown);
00124 
00125         Parameters::parse(parameters, Parameters::kRegForce3DoF(), _force3DoF);
00126         Parameters::parse(parameters, Parameters::kOdomHolonomic(), _holonomic);
00127         Parameters::parse(parameters, Parameters::kOdomGuessMotion(), guessFromMotion_);
00128         Parameters::parse(parameters, Parameters::kOdomFillInfoData(), _fillInfoData);
00129         Parameters::parse(parameters, Parameters::kOdomFilteringStrategy(), _filteringStrategy);
00130         Parameters::parse(parameters, Parameters::kOdomParticleSize(), _particleSize);
00131         Parameters::parse(parameters, Parameters::kOdomParticleNoiseT(), _particleNoiseT);
00132         Parameters::parse(parameters, Parameters::kOdomParticleLambdaT(), _particleLambdaT);
00133         Parameters::parse(parameters, Parameters::kOdomParticleNoiseR(), _particleNoiseR);
00134         Parameters::parse(parameters, Parameters::kOdomParticleLambdaR(), _particleLambdaR);
00135         UASSERT(_particleNoiseT>0);
00136         UASSERT(_particleLambdaT>0);
00137         UASSERT(_particleNoiseR>0);
00138         UASSERT(_particleLambdaR>0);
00139         Parameters::parse(parameters, Parameters::kOdomKalmanProcessNoise(), _kalmanProcessNoise);
00140         Parameters::parse(parameters, Parameters::kOdomKalmanMeasurementNoise(), _kalmanMeasurementNoise);
00141         Parameters::parse(parameters, Parameters::kOdomImageDecimation(), _imageDecimation);
00142         Parameters::parse(parameters, Parameters::kOdomAlignWithGround(), _alignWithGround);
00143         Parameters::parse(parameters, Parameters::kRtabmapPublishRAMUsage(), _publishRAMUsage);
00144         Parameters::parse(parameters, Parameters::kRtabmapImagesAlreadyRectified(), _imagesAlreadyRectified);
00145 
00146         if(_imageDecimation == 0)
00147         {
00148                 _imageDecimation = 1;
00149         }
00150 
00151         if(_filteringStrategy == 2)
00152         {
00153                 // Initialize the Particle filters
00154                 particleFilters_.resize(6);
00155                 for(unsigned int i = 0; i<particleFilters_.size(); ++i)
00156                 {
00157                         if(i<3)
00158                         {
00159                                 particleFilters_[i] = new ParticleFilter(_particleSize, _particleNoiseT, _particleLambdaT);
00160                         }
00161                         else
00162                         {
00163                                 particleFilters_[i] = new ParticleFilter(_particleSize, _particleNoiseR, _particleLambdaR);
00164                         }
00165                 }
00166         }
00167         else if(_filteringStrategy == 1)
00168         {
00169                 initKalmanFilter();
00170         }
00171 }
00172 
00173 Odometry::~Odometry()
00174 {
00175         for(unsigned int i=0; i<particleFilters_.size(); ++i)
00176         {
00177                 delete particleFilters_[i];
00178         }
00179         particleFilters_.clear();
00180 }
00181 
00182 void Odometry::reset(const Transform & initialPose)
00183 {
00184         UASSERT(!initialPose.isNull());
00185         previousVelocityTransform_.setNull();
00186         previousGroundTruthPose_.setNull();
00187         _resetCurrentCount = 0;
00188         previousStamp_ = 0;
00189         distanceTravelled_ = 0;
00190         framesProcessed_ = 0;
00191         if(_force3DoF || particleFilters_.size())
00192         {
00193                 float x,y,z, roll,pitch,yaw;
00194                 initialPose.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
00195 
00196                 if(_force3DoF)
00197                 {
00198                         if(z != 0.0f || roll != 0.0f || pitch != 0.0f)
00199                         {
00200                                 UWARN("Force2D=true and the initial pose contains z, roll or pitch values (%s). They are set to null.", initialPose.prettyPrint().c_str());
00201                         }
00202                         z = 0;
00203                         roll = 0;
00204                         pitch = 0;
00205                         Transform pose(x, y, z, roll, pitch, yaw);
00206                         _pose = pose;
00207                 }
00208                 else
00209                 {
00210                         _pose = initialPose;
00211                 }
00212 
00213                 if(particleFilters_.size())
00214                 {
00215                         UASSERT(particleFilters_.size() == 6);
00216                         particleFilters_[0]->init(x);
00217                         particleFilters_[1]->init(y);
00218                         particleFilters_[2]->init(z);
00219                         particleFilters_[3]->init(roll);
00220                         particleFilters_[4]->init(pitch);
00221                         particleFilters_[5]->init(yaw);
00222                 }
00223 
00224                 if(_filteringStrategy == 1)
00225                 {
00226                         initKalmanFilter(initialPose);
00227                 }
00228         }
00229         else
00230         {
00231                 _pose = initialPose;
00232         }
00233 }
00234 
00235 Transform Odometry::process(SensorData & data, OdometryInfo * info)
00236 {
00237         return process(data, Transform(), info);
00238 }
00239 
00240 Transform Odometry::process(SensorData & data, const Transform & guessIn, OdometryInfo * info)
00241 {
00242         UASSERT_MSG(data.id() >= 0, uFormat("Input data should have ID greater or equal than 0 (id=%d)!", data.id()).c_str());
00243 
00244         if(!_imagesAlreadyRectified && !this->canProcessRawImages())
00245         {
00246                 UERROR("Odometry approach chosen cannot process raw images (not rectified images). Make sure images "
00247                                 "are rectified, and set %s parameter back to true.",
00248                                 Parameters::kRtabmapImagesAlreadyRectified().c_str());
00249         }
00250 
00251         // Ground alignment
00252         if(_pose.isIdentity() && _alignWithGround)
00253         {
00254                 if(data.depthOrRightRaw().empty())
00255                 {
00256                         UWARN("\"%s\" is true but the input has no depth information, ignoring alignment with ground...", Parameters::kOdomAlignWithGround().c_str());
00257                 }
00258                 else
00259                 {
00260                         UTimer alignTimer;
00261                         pcl::IndicesPtr indices(new std::vector<int>);
00262                         pcl::IndicesPtr ground, obstacles;
00263                         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::cloudFromSensorData(data, 1, 10, 0, indices.get());
00264                         bool success = false;
00265                         if(indices->size())
00266                         {
00267                                 cloud = util3d::voxelize(cloud, indices, 0.01);
00268                                 util3d::segmentObstaclesFromGround<pcl::PointXYZ>(cloud, ground, obstacles, 20, M_PI/4.0f, 0.02, 200, true);
00269                                 if(ground->size())
00270                                 {
00271                                         pcl::ModelCoefficients coefficients;
00272                                         util3d::extractPlane(cloud, ground, 0.02, 100, &coefficients);
00273                                         if(coefficients.values.at(3) >= 0)
00274                                         {
00275                                                 UWARN("Ground detected! coefficients=(%f, %f, %f, %f) time=%fs",
00276                                                                 coefficients.values.at(0),
00277                                                                 coefficients.values.at(1),
00278                                                                 coefficients.values.at(2),
00279                                                                 coefficients.values.at(3),
00280                                                                 alignTimer.ticks());
00281                                         }
00282                                         else
00283                                         {
00284                                                 UWARN("Ceiling detected! coefficients=(%f, %f, %f, %f) time=%fs",
00285                                                                 coefficients.values.at(0),
00286                                                                 coefficients.values.at(1),
00287                                                                 coefficients.values.at(2),
00288                                                                 coefficients.values.at(3),
00289                                                                 alignTimer.ticks());
00290                                         }
00291                                         Eigen::Vector3f n(coefficients.values.at(0), coefficients.values.at(1), coefficients.values.at(2));
00292                                         Eigen::Vector3f z(0,0,1);
00293                                         //get rotation from z to n;
00294                                         Eigen::Matrix3f R;
00295                                         R = Eigen::Quaternionf().setFromTwoVectors(n,z);
00296                                         Transform rotation(
00297                                                         R(0,0), R(0,1), R(0,2), 0,
00298                                                         R(1,0), R(1,1), R(1,2), 0,
00299                                                         R(2,0), R(2,1), R(2,2), coefficients.values.at(3));
00300                                         this->reset(rotation);
00301                                         success = true;
00302                                 }
00303                         }
00304                         if(!success)
00305                         {
00306                                 UERROR("Odometry failed to detect the ground. You have this "
00307                                                 "error because parameter \"%s\" is true. "
00308                                                 "Make sure the camera is seeing the ground (e.g., tilt ~30 "
00309                                                 "degrees toward the ground).", Parameters::kOdomAlignWithGround().c_str());
00310                         }
00311                 }
00312         }
00313 
00314         // KITTI datasets start with stamp=0
00315         double dt = previousStamp_>0.0f || (previousStamp_==0.0f && framesProcessed()==1)?data.stamp() - previousStamp_:0.0;
00316         Transform guess = dt>0.0 && guessFromMotion_ && !previousVelocityTransform_.isNull()?Transform::getIdentity():Transform();
00317         if(!(dt>0.0 || (dt == 0.0 && previousVelocityTransform_.isNull())))
00318         {
00319                 if(guessFromMotion_ && !data.imageRaw().empty())
00320                 {
00321                         UERROR("Guess from motion is set but dt is invalid! Odometry is then computed without guess. (dt=%f previous transform=%s)", dt, previousVelocityTransform_.prettyPrint().c_str());
00322                 }
00323                 else if(_filteringStrategy==1)
00324                 {
00325                         UERROR("Kalman filtering is enalbed but dt is invalid! Odometry is then computed without Kalman filtering. (dt=%f previous transform=%s)", dt, previousVelocityTransform_.prettyPrint().c_str());
00326                 }
00327                 dt=0;
00328                 previousVelocityTransform_.setNull();
00329         }
00330         if(!previousVelocityTransform_.isNull())
00331         {
00332                 if(guessFromMotion_)
00333                 {
00334                         if(_filteringStrategy == 1)
00335                         {
00336                                 // use Kalman predict transform
00337                                 float vx,vy,vz, vroll,vpitch,vyaw;
00338                                 predictKalmanFilter(dt, &vx,&vy,&vz,&vroll,&vpitch,&vyaw);
00339                                 guess = Transform(vx*dt, vy*dt, vz*dt, vroll*dt, vpitch*dt, vyaw*dt);
00340                         }
00341                         else
00342                         {
00343                                 float vx,vy,vz, vroll,vpitch,vyaw;
00344                                 previousVelocityTransform_.getTranslationAndEulerAngles(vx,vy,vz, vroll,vpitch,vyaw);
00345                                 guess = Transform(vx*dt, vy*dt, vz*dt, vroll*dt, vpitch*dt, vyaw*dt);
00346                         }
00347                 }
00348                 else if(_filteringStrategy == 1)
00349                 {
00350                         predictKalmanFilter(dt);
00351                 }
00352         }
00353 
00354         if(!guessIn.isNull())
00355         {
00356                 guess = guessIn;
00357         }
00358 
00359         UTimer time;
00360         Transform t;
00361         if(_imageDecimation > 1 && !data.imageRaw().empty())
00362         {
00363                 // Decimation of images with calibrations
00364                 SensorData decimatedData = data;
00365                 decimatedData.setImageRaw(util2d::decimate(decimatedData.imageRaw(), _imageDecimation));
00366                 decimatedData.setDepthOrRightRaw(util2d::decimate(decimatedData.depthOrRightRaw(), _imageDecimation));
00367                 std::vector<CameraModel> cameraModels = decimatedData.cameraModels();
00368                 for(unsigned int i=0; i<cameraModels.size(); ++i)
00369                 {
00370                         cameraModels[i] = cameraModels[i].scaled(1.0/double(_imageDecimation));
00371                 }
00372                 decimatedData.setCameraModels(cameraModels);
00373                 StereoCameraModel stereoModel = decimatedData.stereoCameraModel();
00374                 if(stereoModel.isValidForProjection())
00375                 {
00376                         stereoModel.scale(1.0/double(_imageDecimation));
00377                 }
00378                 decimatedData.setStereoCameraModel(stereoModel);
00379 
00380                 // compute transform
00381                 t = this->computeTransform(decimatedData, guess, info);
00382 
00383                 // transform back the keypoints in the original image
00384                 std::vector<cv::KeyPoint> kpts = decimatedData.keypoints();
00385                 double log2value = log(double(_imageDecimation))/log(2.0);
00386                 for(unsigned int i=0; i<kpts.size(); ++i)
00387                 {
00388                         kpts[i].pt.x *= _imageDecimation;
00389                         kpts[i].pt.y *= _imageDecimation;
00390                         kpts[i].size *= _imageDecimation;
00391                         kpts[i].octave += log2value;
00392                 }
00393                 data.setFeatures(kpts, decimatedData.keypoints3D(), decimatedData.descriptors());
00394 
00395                 if(info)
00396                 {
00397                         UASSERT(info->newCorners.size() == info->refCorners.size());
00398                         for(unsigned int i=0; i<info->newCorners.size(); ++i)
00399                         {
00400                                 info->refCorners[i].x *= _imageDecimation;
00401                                 info->refCorners[i].y *= _imageDecimation;
00402                                 info->newCorners[i].x *= _imageDecimation;
00403                                 info->newCorners[i].y *= _imageDecimation;
00404                         }
00405                         for(std::multimap<int, cv::KeyPoint>::iterator iter=info->words.begin(); iter!=info->words.end(); ++iter)
00406                         {
00407                                 iter->second.pt.x *= _imageDecimation;
00408                                 iter->second.pt.y *= _imageDecimation;
00409                                 iter->second.size *= _imageDecimation;
00410                                 iter->second.octave += log2value;
00411                         }
00412                 }
00413         }
00414         else
00415         {
00416                 t = this->computeTransform(data, guess, info);
00417         }
00418 
00419         if(info)
00420         {
00421                 info->timeEstimation = time.ticks();
00422                 info->lost = t.isNull();
00423                 info->stamp = data.stamp();
00424                 info->interval = dt;
00425                 info->transform = t;
00426                 if(_publishRAMUsage)
00427                 {
00428                         info->memoryUsage = UProcessInfo::getMemoryUsage()/(1024*1024);
00429                 }
00430 
00431                 if(!data.groundTruth().isNull())
00432                 {
00433                         if(!previousGroundTruthPose_.isNull())
00434                         {
00435                                 info->transformGroundTruth = previousGroundTruthPose_.inverse() * data.groundTruth();
00436                         }
00437                         previousGroundTruthPose_ = data.groundTruth();
00438                 }
00439         }
00440 
00441         if(!t.isNull())
00442         {
00443                 _resetCurrentCount = _resetCountdown;
00444 
00445                 float vx,vy,vz, vroll,vpitch,vyaw;
00446                 t.getTranslationAndEulerAngles(vx,vy,vz, vroll,vpitch,vyaw);
00447 
00448                 // transform to velocity
00449                 if(dt)
00450                 {
00451                         vx /= dt;
00452                         vy /= dt;
00453                         vz /= dt;
00454                         vroll /= dt;
00455                         vpitch /= dt;
00456                         vyaw /= dt;
00457                 }
00458 
00459                 if(_force3DoF || !_holonomic || particleFilters_.size() || _filteringStrategy==1)
00460                 {
00461                         if(_filteringStrategy == 1)
00462                         {
00463                                 if(previousVelocityTransform_.isNull())
00464                                 {
00465                                         // reset Kalman
00466                                         if(dt)
00467                                         {
00468                                                 initKalmanFilter(t, vx,vy,vz,vroll,vpitch,vyaw);
00469                                         }
00470                                         else
00471                                         {
00472                                                 initKalmanFilter(t);
00473                                         }
00474                                 }
00475                                 else
00476                                 {
00477                                         // Kalman filtering
00478                                         updateKalmanFilter(vx,vy,vz,vroll,vpitch,vyaw);
00479                                 }
00480                         }
00481                         else if(particleFilters_.size())
00482                         {
00483                                 // Particle filtering
00484                                 UASSERT(particleFilters_.size()==6);
00485                                 if(previousVelocityTransform_.isNull())
00486                                 {
00487                                         particleFilters_[0]->init(vx);
00488                                         particleFilters_[1]->init(vy);
00489                                         particleFilters_[2]->init(vz);
00490                                         particleFilters_[3]->init(vroll);
00491                                         particleFilters_[4]->init(vpitch);
00492                                         particleFilters_[5]->init(vyaw);
00493                                 }
00494                                 else
00495                                 {
00496                                         vx = particleFilters_[0]->filter(vx);
00497                                         vy = particleFilters_[1]->filter(vy);
00498                                         vyaw = particleFilters_[5]->filter(vyaw);
00499 
00500                                         if(!_holonomic)
00501                                         {
00502                                                 // arc trajectory around ICR
00503                                                 float tmpY = vyaw!=0.0f ? vx / tan((CV_PI-vyaw)/2.0f) : 0.0f;
00504                                                 if(fabs(tmpY) < fabs(vy) || (tmpY<=0 && vy >=0) || (tmpY>=0 && vy<=0))
00505                                                 {
00506                                                         vy = tmpY;
00507                                                 }
00508                                                 else
00509                                                 {
00510                                                         vyaw = (atan(vx/vy)*2.0f-CV_PI)*-1;
00511                                                 }
00512                                         }
00513 
00514                                         if(!_force3DoF)
00515                                         {
00516                                                 vz = particleFilters_[2]->filter(vz);
00517                                                 vroll = particleFilters_[3]->filter(vroll);
00518                                                 vpitch = particleFilters_[4]->filter(vpitch);
00519                                         }
00520                                 }
00521 
00522                                 if(info)
00523                                 {
00524                                         info->timeParticleFiltering = time.ticks();
00525                                 }
00526 
00527                                 if(_force3DoF)
00528                                 {
00529                                         vz = 0.0f;
00530                                         vroll = 0.0f;
00531                                         vpitch = 0.0f;
00532                                 }
00533                         }
00534                         else if(!_holonomic)
00535                         {
00536                                 // arc trajectory around ICR
00537                                 vy = vyaw!=0.0f ? vx / tan((CV_PI-vyaw)/2.0f) : 0.0f;
00538                                 if(_force3DoF)
00539                                 {
00540                                         vz = 0.0f;
00541                                         vroll = 0.0f;
00542                                         vpitch = 0.0f;
00543                                 }
00544                         }
00545 
00546                         if(dt)
00547                         {
00548                                 t = Transform(vx*dt, vy*dt, vz*dt, vroll*dt, vpitch*dt, vyaw*dt);
00549                         }
00550                         else
00551                         {
00552                                 t = Transform(vx, vy, vz, vroll, vpitch, vyaw);
00553                         }
00554 
00555                         if(info)
00556                         {
00557                                 info->transformFiltered = t;
00558                         }
00559                 }
00560 
00561                 if(data.stamp() == 0 && framesProcessed_ != 0)
00562                 {
00563                         UWARN("Null stamp detected");
00564                 }
00565 
00566                 previousStamp_ = data.stamp();
00567                 previousVelocityTransform_.setNull();
00568 
00569                 if(dt)
00570                 {
00571                         previousVelocityTransform_ = Transform(vx, vy, vz, vroll, vpitch, vyaw);
00572                 }
00573 
00574                 if(info)
00575                 {
00576                         distanceTravelled_ += t.getNorm();
00577                         info->distanceTravelled = distanceTravelled_;
00578                 }
00579                 ++framesProcessed_;
00580 
00581                 return _pose *= t; // update
00582         }
00583         else if(_resetCurrentCount > 0)
00584         {
00585                 UWARN("Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", _resetCurrentCount);
00586 
00587                 --_resetCurrentCount;
00588                 if(_resetCurrentCount == 0)
00589                 {
00590                         UWARN("Odometry automatically reset to latest pose!");
00591                         this->reset(_pose);
00592                 }
00593         }
00594 
00595         previousVelocityTransform_.setNull();
00596         previousStamp_ = 0;
00597 
00598         return Transform();
00599 }
00600 
00601 void Odometry::initKalmanFilter(const Transform & initialPose, float vx, float vy, float vz, float vroll, float vpitch, float vyaw)
00602 {
00603         UDEBUG("");
00604         // See OpenCV tutorial: http://docs.opencv.org/master/dc/d2c/tutorial_real_time_pose.html
00605         // See Kalman filter pose/orientation estimation theory: http://campar.in.tum.de/Chair/KalmanFilter
00606 
00607         // initialize the Kalman filter
00608         int nStates = 18;            // the number of states (x,y,z,x',y',z',x'',y'',z'',roll,pitch,yaw,roll',pitch',yaw',roll'',pitch'',yaw'')
00609         int nMeasurements = 6;       // the number of measured states (x',y',z',roll',pitch',yaw')
00610         if(_force3DoF)
00611         {
00612                 nStates = 9;             // the number of states (x,y,x',y',x'',y'',yaw,yaw',yaw'')
00613                 nMeasurements = 3;       // the number of measured states (x',y',yaw')
00614         }
00615         int nInputs = 0;             // the number of action control
00616 
00617         /* From viso2, measurement covariance
00618          * static const boost::array<double, 36> STANDARD_POSE_COVARIANCE =
00619         { { 0.1, 0, 0, 0, 0, 0,
00620             0, 0.1, 0, 0, 0, 0,
00621             0, 0, 0.1, 0, 0, 0,
00622             0, 0, 0, 0.17, 0, 0,
00623             0, 0, 0, 0, 0.17, 0,
00624             0, 0, 0, 0, 0, 0.17 } };
00625         static const boost::array<double, 36> STANDARD_TWIST_COVARIANCE =
00626         { { 0.05, 0, 0, 0, 0, 0,
00627             0, 0.05, 0, 0, 0, 0,
00628             0, 0, 0.05, 0, 0, 0,
00629             0, 0, 0, 0.09, 0, 0,
00630             0, 0, 0, 0, 0.09, 0,
00631             0, 0, 0, 0, 0, 0.09 } };
00632          */
00633 
00634 
00635         kalmanFilter_.init(nStates, nMeasurements, nInputs);                 // init Kalman Filter
00636         cv::setIdentity(kalmanFilter_.processNoiseCov, cv::Scalar::all(_kalmanProcessNoise));  // set process noise
00637         cv::setIdentity(kalmanFilter_.measurementNoiseCov, cv::Scalar::all(_kalmanMeasurementNoise));   // set measurement noise
00638         cv::setIdentity(kalmanFilter_.errorCovPost, cv::Scalar::all(1));             // error covariance
00639 
00640         float x,y,z,roll,pitch,yaw;
00641         initialPose.getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
00642 
00643         if(_force3DoF)
00644         {
00645         /* MEASUREMENT MODEL (velocity) */
00646                 //  [0 0 1 0 0 0 0 0 0]
00647                 //  [0 0 0 1 0 0 0 0 0]
00648                 //  [0 0 0 0 0 0 0 1 0]
00649                 kalmanFilter_.measurementMatrix.at<float>(0,2) = 1;  // x'
00650                 kalmanFilter_.measurementMatrix.at<float>(1,3) = 1;  // y'
00651                 kalmanFilter_.measurementMatrix.at<float>(2,7) = 1; // yaw'
00652 
00653                 kalmanFilter_.statePost.at<float>(0) = x;
00654                 kalmanFilter_.statePost.at<float>(1) = y;
00655                 kalmanFilter_.statePost.at<float>(6) = yaw;
00656 
00657                 kalmanFilter_.statePost.at<float>(2) = vx;
00658                 kalmanFilter_.statePost.at<float>(3) = vy;
00659                 kalmanFilter_.statePost.at<float>(7) = vyaw;
00660         }
00661         else
00662         {
00663             /* MEASUREMENT MODEL (velocity) */
00664                 //  [0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
00665                 //  [0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0]
00666                 //  [0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0]
00667                 //  [0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0]
00668                 //  [0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0]
00669                 //  [0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0]
00670                 kalmanFilter_.measurementMatrix.at<float>(0,3) = 1;  // x'
00671                 kalmanFilter_.measurementMatrix.at<float>(1,4) = 1;  // y'
00672                 kalmanFilter_.measurementMatrix.at<float>(2,5) = 1;  // z'
00673                 kalmanFilter_.measurementMatrix.at<float>(3,12) = 1; // roll'
00674                 kalmanFilter_.measurementMatrix.at<float>(4,13) = 1; // pitch'
00675                 kalmanFilter_.measurementMatrix.at<float>(5,14) = 1; // yaw'
00676 
00677                 kalmanFilter_.statePost.at<float>(0) = x;
00678                 kalmanFilter_.statePost.at<float>(1) = y;
00679                 kalmanFilter_.statePost.at<float>(2) = z;
00680                 kalmanFilter_.statePost.at<float>(9) = roll;
00681                 kalmanFilter_.statePost.at<float>(10) = pitch;
00682                 kalmanFilter_.statePost.at<float>(11) = yaw;
00683 
00684                 kalmanFilter_.statePost.at<float>(3) = vx;
00685                 kalmanFilter_.statePost.at<float>(4) = vy;
00686                 kalmanFilter_.statePost.at<float>(5) = vz;
00687                 kalmanFilter_.statePost.at<float>(12) = vroll;
00688                 kalmanFilter_.statePost.at<float>(13) = vpitch;
00689                 kalmanFilter_.statePost.at<float>(14) = vyaw;
00690         }
00691 }
00692 
00693 void Odometry::predictKalmanFilter(float dt, float * vx, float * vy, float * vz, float * vroll, float * vpitch, float * vyaw)
00694 {
00695         // Set transition matrix with current dt
00696         if(_force3DoF)
00697         {
00698                 // 2D:
00699                 //  [1 0 dt  0 dt2    0   0    0     0] x
00700                 //  [0 1  0 dt   0  dt2   0    0     0] y
00701                 //  [0 0  1  0   dt   0   0    0     0] x'
00702                 //  [0 0  0  1   0   dt   0    0     0] y'
00703                 //  [0 0  0  0   1    0   0    0     0] x''
00704                 //  [0 0  0  0   0    0   0    0     0] y''
00705                 //  [0 0  0  0   0    0   1   dt   dt2] yaw
00706                 //  [0 0  0  0   0    0   0    1    dt] yaw'
00707                 //  [0 0  0  0   0    0   0    0     1] yaw''
00708                 kalmanFilter_.transitionMatrix.at<float>(0,2) = dt;
00709                 kalmanFilter_.transitionMatrix.at<float>(1,3) = dt;
00710                 kalmanFilter_.transitionMatrix.at<float>(2,4) = dt;
00711                 kalmanFilter_.transitionMatrix.at<float>(3,5) = dt;
00712                 kalmanFilter_.transitionMatrix.at<float>(0,4) = 0.5*pow(dt,2);
00713                 kalmanFilter_.transitionMatrix.at<float>(1,5) = 0.5*pow(dt,2);
00714                 // orientation
00715                 kalmanFilter_.transitionMatrix.at<float>(6,7) = dt;
00716                 kalmanFilter_.transitionMatrix.at<float>(7,8) = dt;
00717                 kalmanFilter_.transitionMatrix.at<float>(6,8) = 0.5*pow(dt,2);
00718         }
00719         else
00720         {
00721                 //  [1 0 0 dt  0  0 dt2   0   0 0 0 0  0  0  0   0   0   0] x
00722                 //  [0 1 0  0 dt  0   0 dt2   0 0 0 0  0  0  0   0   0   0] y
00723                 //  [0 0 1  0  0 dt   0   0 dt2 0 0 0  0  0  0   0   0   0] z
00724                 //  [0 0 0  1  0  0  dt   0   0 0 0 0  0  0  0   0   0   0] x'
00725                 //  [0 0 0  0  1  0   0  dt   0 0 0 0  0  0  0   0   0   0] y'
00726                 //  [0 0 0  0  0  1   0   0  dt 0 0 0  0  0  0   0   0   0] z'
00727                 //  [0 0 0  0  0  0   1   0   0 0 0 0  0  0  0   0   0   0] x''
00728                 //  [0 0 0  0  0  0   0   1   0 0 0 0  0  0  0   0   0   0] y''
00729                 //  [0 0 0  0  0  0   0   0   1 0 0 0  0  0  0   0   0   0] z''
00730                 //  [0 0 0  0  0  0   0   0   0 1 0 0 dt  0  0 dt2   0   0]
00731                 //  [0 0 0  0  0  0   0   0   0 0 1 0  0 dt  0   0 dt2   0]
00732                 //  [0 0 0  0  0  0   0   0   0 0 0 1  0  0 dt   0   0 dt2]
00733                 //  [0 0 0  0  0  0   0   0   0 0 0 0  1  0  0  dt   0   0]
00734                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  1  0   0  dt   0]
00735                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  1   0   0  dt]
00736                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  0   1   0   0]
00737                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  0   0   1   0]
00738                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  0   0   0   1]
00739                 // position
00740                 kalmanFilter_.transitionMatrix.at<float>(0,3) = dt;
00741                 kalmanFilter_.transitionMatrix.at<float>(1,4) = dt;
00742                 kalmanFilter_.transitionMatrix.at<float>(2,5) = dt;
00743                 kalmanFilter_.transitionMatrix.at<float>(3,6) = dt;
00744                 kalmanFilter_.transitionMatrix.at<float>(4,7) = dt;
00745                 kalmanFilter_.transitionMatrix.at<float>(5,8) = dt;
00746                 kalmanFilter_.transitionMatrix.at<float>(0,6) = 0.5*pow(dt,2);
00747                 kalmanFilter_.transitionMatrix.at<float>(1,7) = 0.5*pow(dt,2);
00748                 kalmanFilter_.transitionMatrix.at<float>(2,8) = 0.5*pow(dt,2);
00749                 // orientation
00750                 kalmanFilter_.transitionMatrix.at<float>(9,12) = dt;
00751                 kalmanFilter_.transitionMatrix.at<float>(10,13) = dt;
00752                 kalmanFilter_.transitionMatrix.at<float>(11,14) = dt;
00753                 kalmanFilter_.transitionMatrix.at<float>(12,15) = dt;
00754                 kalmanFilter_.transitionMatrix.at<float>(13,16) = dt;
00755                 kalmanFilter_.transitionMatrix.at<float>(14,17) = dt;
00756                 kalmanFilter_.transitionMatrix.at<float>(9,15) = 0.5*pow(dt,2);
00757                 kalmanFilter_.transitionMatrix.at<float>(10,16) = 0.5*pow(dt,2);
00758                 kalmanFilter_.transitionMatrix.at<float>(11,17) = 0.5*pow(dt,2);
00759         }
00760 
00761         // First predict, to update the internal statePre variable
00762         UDEBUG("Predict");
00763         const cv::Mat & prediction = kalmanFilter_.predict();
00764 
00765         if(vx)
00766                 *vx = prediction.at<float>(3);                      // x'
00767         if(vy)
00768                 *vy = prediction.at<float>(4);                      // y'
00769         if(vz)
00770                 *vz = _force3DoF?0.0f:prediction.at<float>(5);      // z'
00771         if(vroll)
00772                 *vroll = _force3DoF?0.0f:prediction.at<float>(12);  // roll'
00773         if(vpitch)
00774                 *vpitch = _force3DoF?0.0f:prediction.at<float>(13); // pitch'
00775         if(vyaw)
00776                 *vyaw = prediction.at<float>(_force3DoF?7:14);      // yaw'
00777 }
00778 
00779 void Odometry::updateKalmanFilter(float & vx, float & vy, float & vz, float & vroll, float & vpitch, float & vyaw)
00780 {
00781         // Set measurement to predict
00782         cv::Mat measurements;
00783         if(!_force3DoF)
00784         {
00785                 measurements = cv::Mat(6,1,CV_32FC1);
00786                 measurements.at<float>(0) = vx;     // x'
00787                 measurements.at<float>(1) = vy;     // y'
00788                 measurements.at<float>(2) = vz;     // z'
00789                 measurements.at<float>(3) = vroll;  // roll'
00790                 measurements.at<float>(4) = vpitch; // pitch'
00791                 measurements.at<float>(5) = vyaw;   // yaw'
00792         }
00793         else
00794         {
00795                 measurements = cv::Mat(3,1,CV_32FC1);
00796                 measurements.at<float>(0) = vx;     // x'
00797                 measurements.at<float>(1) = vy;     // y'
00798                 measurements.at<float>(2) = vyaw;   // yaw',
00799         }
00800 
00801         // The "correct" phase that is going to use the predicted value and our measurement
00802         UDEBUG("Correct");
00803         const cv::Mat & estimated = kalmanFilter_.correct(measurements);
00804 
00805 
00806         vx = estimated.at<float>(3);                      // x'
00807         vy = estimated.at<float>(4);                      // y'
00808         vz = _force3DoF?0.0f:estimated.at<float>(5);      // z'
00809         vroll = _force3DoF?0.0f:estimated.at<float>(12);  // roll'
00810         vpitch = _force3DoF?0.0f:estimated.at<float>(13); // pitch'
00811         vyaw = estimated.at<float>(_force3DoF?7:14);      // yaw'
00812 }
00813 
00814 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:21