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/OdometryInfo.h"
00032 #include "rtabmap/core/util3d.h"
00033 #include "rtabmap/core/util3d_mapping.h"
00034 #include "rtabmap/core/util3d_filtering.h"
00035 #include "rtabmap/utilite/ULogger.h"
00036 #include "rtabmap/utilite/UTimer.h"
00037 #include "rtabmap/utilite/UConversion.h"
00038 #include "rtabmap/core/ParticleFilter.h"
00039 #include "rtabmap/core/util2d.h"
00040 
00041 #include <pcl/pcl_base.h>
00042 
00043 namespace rtabmap {
00044 
00045 Odometry * Odometry::create(const ParametersMap & parameters)
00046 {
00047         int odomTypeInt = Parameters::defaultOdomStrategy();
00048         Parameters::parse(parameters, Parameters::kOdomStrategy(), odomTypeInt);
00049         Odometry::Type type = (Odometry::Type)odomTypeInt;
00050         return create(type, parameters);
00051 }
00052 
00053 Odometry * Odometry::create(Odometry::Type & type, const ParametersMap & parameters)
00054 {
00055         UDEBUG("type=%d", (int)type);
00056         Odometry * odometry = 0;
00057         switch(type)
00058         {
00059         case Odometry::kTypeF2F:
00060                 odometry = new OdometryF2F(parameters);
00061                 break;
00062         default:
00063                 odometry = new OdometryF2M(parameters);
00064                 type = Odometry::kTypeLocalMap;
00065                 break;
00066         }
00067         return odometry;
00068 }
00069 
00070 Odometry::Odometry(const rtabmap::ParametersMap & parameters) :
00071                 _resetCountdown(Parameters::defaultOdomResetCountdown()),
00072                 _force3DoF(Parameters::defaultRegForce3DoF()),
00073                 _holonomic(Parameters::defaultOdomHolonomic()),
00074                 guessFromMotion_(Parameters::defaultOdomGuessMotion()),
00075                 _filteringStrategy(Parameters::defaultOdomFilteringStrategy()),
00076                 _particleSize(Parameters::defaultOdomParticleSize()),
00077                 _particleNoiseT(Parameters::defaultOdomParticleNoiseT()),
00078                 _particleLambdaT(Parameters::defaultOdomParticleLambdaT()),
00079                 _particleNoiseR(Parameters::defaultOdomParticleNoiseR()),
00080                 _particleLambdaR(Parameters::defaultOdomParticleLambdaR()),
00081                 _fillInfoData(Parameters::defaultOdomFillInfoData()),
00082                 _kalmanProcessNoise(Parameters::defaultOdomKalmanProcessNoise()),
00083                 _kalmanMeasurementNoise(Parameters::defaultOdomKalmanMeasurementNoise()),
00084                 _imageDecimation(Parameters::defaultOdomImageDecimation()),
00085                 _alignWithGround(Parameters::defaultOdomAlignWithGround()),
00086                 _pose(Transform::getIdentity()),
00087                 _resetCurrentCount(0),
00088                 previousStamp_(0),
00089                 distanceTravelled_(0)
00090 {
00091         Parameters::parse(parameters, Parameters::kOdomResetCountdown(), _resetCountdown);
00092 
00093         Parameters::parse(parameters, Parameters::kRegForce3DoF(), _force3DoF);
00094         Parameters::parse(parameters, Parameters::kOdomHolonomic(), _holonomic);
00095         Parameters::parse(parameters, Parameters::kOdomGuessMotion(), guessFromMotion_);
00096         Parameters::parse(parameters, Parameters::kOdomFillInfoData(), _fillInfoData);
00097         Parameters::parse(parameters, Parameters::kOdomFilteringStrategy(), _filteringStrategy);
00098         Parameters::parse(parameters, Parameters::kOdomParticleSize(), _particleSize);
00099         Parameters::parse(parameters, Parameters::kOdomParticleNoiseT(), _particleNoiseT);
00100         Parameters::parse(parameters, Parameters::kOdomParticleLambdaT(), _particleLambdaT);
00101         Parameters::parse(parameters, Parameters::kOdomParticleNoiseR(), _particleNoiseR);
00102         Parameters::parse(parameters, Parameters::kOdomParticleLambdaR(), _particleLambdaR);
00103         UASSERT(_particleNoiseT>0);
00104         UASSERT(_particleLambdaT>0);
00105         UASSERT(_particleNoiseR>0);
00106         UASSERT(_particleLambdaR>0);
00107         Parameters::parse(parameters, Parameters::kOdomKalmanProcessNoise(), _kalmanProcessNoise);
00108         Parameters::parse(parameters, Parameters::kOdomKalmanMeasurementNoise(), _kalmanMeasurementNoise);
00109         Parameters::parse(parameters, Parameters::kOdomImageDecimation(), _imageDecimation);
00110         Parameters::parse(parameters, Parameters::kOdomAlignWithGround(), _alignWithGround);
00111         UASSERT(_imageDecimation>=1);
00112 
00113         if(_filteringStrategy == 2)
00114         {
00115                 // Initialize the Particle filters
00116                 particleFilters_.resize(6);
00117                 for(unsigned int i = 0; i<particleFilters_.size(); ++i)
00118                 {
00119                         if(i<3)
00120                         {
00121                                 particleFilters_[i] = new ParticleFilter(_particleSize, _particleNoiseT, _particleLambdaT);
00122                         }
00123                         else
00124                         {
00125                                 particleFilters_[i] = new ParticleFilter(_particleSize, _particleNoiseR, _particleLambdaR);
00126                         }
00127                 }
00128         }
00129         else if(_filteringStrategy == 1)
00130         {
00131                 initKalmanFilter();
00132         }
00133 }
00134 
00135 Odometry::~Odometry()
00136 {
00137         for(unsigned int i=0; i<particleFilters_.size(); ++i)
00138         {
00139                 delete particleFilters_[i];
00140         }
00141         particleFilters_.clear();
00142 }
00143 
00144 void Odometry::reset(const Transform & initialPose)
00145 {
00146         UASSERT(!initialPose.isNull());
00147         previousVelocityTransform_.setNull();
00148         previousGroundTruthPose_.setNull();
00149         _resetCurrentCount = 0;
00150         previousStamp_ = 0;
00151         distanceTravelled_ = 0;
00152         if(_force3DoF || particleFilters_.size())
00153         {
00154                 float x,y,z, roll,pitch,yaw;
00155                 initialPose.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
00156 
00157                 if(_force3DoF)
00158                 {
00159                         if(z != 0.0f || roll != 0.0f || pitch != 0.0f)
00160                         {
00161                                 UWARN("Force2D=true and the initial pose contains z, roll or pitch values (%s). They are set to null.", initialPose.prettyPrint().c_str());
00162                         }
00163                         z = 0;
00164                         roll = 0;
00165                         pitch = 0;
00166                         Transform pose(x, y, z, roll, pitch, yaw);
00167                         _pose = pose;
00168                 }
00169                 else
00170                 {
00171                         _pose = initialPose;
00172                 }
00173 
00174                 if(particleFilters_.size())
00175                 {
00176                         UASSERT(particleFilters_.size() == 6);
00177                         particleFilters_[0]->init(x);
00178                         particleFilters_[1]->init(y);
00179                         particleFilters_[2]->init(z);
00180                         particleFilters_[3]->init(roll);
00181                         particleFilters_[4]->init(pitch);
00182                         particleFilters_[5]->init(yaw);
00183                 }
00184 
00185                 if(_filteringStrategy == 1)
00186                 {
00187                         initKalmanFilter(initialPose);
00188                 }
00189         }
00190         else
00191         {
00192                 _pose = initialPose;
00193         }
00194 }
00195 
00196 Transform Odometry::process(SensorData & data, OdometryInfo * info)
00197 {
00198         return process(data, Transform(), info);
00199 }
00200 
00201 Transform Odometry::process(SensorData & data, const Transform & guessIn, OdometryInfo * info)
00202 {
00203         UASSERT(!data.imageRaw().empty());
00204 
00205         // Ground alignment
00206         if(_pose.isIdentity() && _alignWithGround)
00207         {
00208                 UTimer alignTimer;
00209                 pcl::IndicesPtr indices(new std::vector<int>);
00210                 pcl::IndicesPtr ground, obstacles;
00211                 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = util3d::cloudFromSensorData(data, 1, 0, 0, indices.get());
00212                 cloud = util3d::voxelize(cloud, indices, 0.01);
00213                 bool success = false;
00214                 if(cloud->size())
00215                 {
00216                         util3d::segmentObstaclesFromGround<pcl::PointXYZ>(cloud, ground, obstacles, 20, M_PI/4.0f, 0.02, 200, true);
00217                         if(ground->size())
00218                         {
00219                                 pcl::ModelCoefficients coefficients;
00220                                 util3d::extractPlane(cloud, ground, 0.02, 100, &coefficients);
00221                                 if(coefficients.values.at(3) >= 0)
00222                                 {
00223                                         UWARN("Ground detected! coefficients=(%f, %f, %f, %f) time=%fs",
00224                                                         coefficients.values.at(0),
00225                                                         coefficients.values.at(1),
00226                                                         coefficients.values.at(2),
00227                                                         coefficients.values.at(3),
00228                                                         alignTimer.ticks());
00229                                 }
00230                                 else
00231                                 {
00232                                         UWARN("Ceiling detected! coefficients=(%f, %f, %f, %f) time=%fs",
00233                                                         coefficients.values.at(0),
00234                                                         coefficients.values.at(1),
00235                                                         coefficients.values.at(2),
00236                                                         coefficients.values.at(3),
00237                                                         alignTimer.ticks());
00238                                 }
00239                                 Eigen::Vector3f n(coefficients.values.at(0), coefficients.values.at(1), coefficients.values.at(2));
00240                                 Eigen::Vector3f z(0,0,1);
00241                                 //get rotation from z to n;
00242                                 Eigen::Matrix3f R;
00243                                 R = Eigen::Quaternionf().setFromTwoVectors(n,z);
00244                                 Transform rotation(
00245                                                 R(0,0), R(0,1), R(0,2), 0,
00246                                                 R(1,0), R(1,1), R(1,2), 0,
00247                                                 R(2,0), R(2,1), R(2,2), coefficients.values.at(3));
00248                                 _pose *= rotation;
00249                                 success = true;
00250                         }
00251                 }
00252                 if(!success)
00253                 {
00254                         UERROR("Odometry failed to detect the ground. You have this "
00255                                         "error because parameter \"Odom/AlignWithGround\" is true. "
00256                                         "Make sure the camera is seeing the ground (e.g., tilt ~30 "
00257                                         "degrees toward the ground).");
00258                 }
00259         }
00260 
00261         if(!data.stereoCameraModel().isValidForProjection() &&
00262            (data.cameraModels().size() == 0 || !data.cameraModels()[0].isValidForProjection()))
00263         {
00264                 UERROR("Rectified images required! Calibrate your camera.");
00265                 return Transform();
00266         }
00267 
00268         double dt = previousStamp_>0.0f?data.stamp() - previousStamp_:0.0;
00269         Transform guess = dt && guessFromMotion_ && !previousVelocityTransform_.isNull()?Transform::getIdentity():Transform();
00270         UASSERT_MSG(dt>0.0 || (dt == 0.0 && previousVelocityTransform_.isNull()), uFormat("dt=%f previous transform=%s", dt, previousVelocityTransform_.prettyPrint().c_str()).c_str());
00271         if(!previousVelocityTransform_.isNull())
00272         {
00273                 if(guessFromMotion_)
00274                 {
00275                         if(_filteringStrategy == 1)
00276                         {
00277                                 // use Kalman predict transform
00278                                 float vx,vy,vz, vroll,vpitch,vyaw;
00279                                 predictKalmanFilter(dt, &vx,&vy,&vz,&vroll,&vpitch,&vyaw);
00280                                 guess = Transform(vx*dt, vy*dt, vz*dt, vroll*dt, vpitch*dt, vyaw*dt);
00281                         }
00282                         else
00283                         {
00284                                 float vx,vy,vz, vroll,vpitch,vyaw;
00285                                 previousVelocityTransform_.getTranslationAndEulerAngles(vx,vy,vz, vroll,vpitch,vyaw);
00286                                 guess = Transform(vx*dt, vy*dt, vz*dt, vroll*dt, vpitch*dt, vyaw*dt);
00287                         }
00288                 }
00289                 else if(_filteringStrategy == 1)
00290                 {
00291                         predictKalmanFilter(dt);
00292                 }
00293         }
00294 
00295         if(!guessIn.isNull())
00296         {
00297                 guess = guessIn;
00298         }
00299 
00300         UTimer time;
00301         Transform t;
00302         if(_imageDecimation > 1)
00303         {
00304                 // Decimation of images with calibrations
00305                 SensorData decimatedData = data;
00306                 decimatedData.setImageRaw(util2d::decimate(decimatedData.imageRaw(), _imageDecimation));
00307                 decimatedData.setDepthOrRightRaw(util2d::decimate(decimatedData.depthOrRightRaw(), _imageDecimation));
00308                 std::vector<CameraModel> cameraModels = decimatedData.cameraModels();
00309                 for(unsigned int i=0; i<cameraModels.size(); ++i)
00310                 {
00311                         cameraModels[i] = cameraModels[i].scaled(1.0/double(_imageDecimation));
00312                 }
00313                 decimatedData.setCameraModels(cameraModels);
00314                 StereoCameraModel stereoModel = decimatedData.stereoCameraModel();
00315                 if(stereoModel.isValidForProjection())
00316                 {
00317                         stereoModel.scale(1.0/double(_imageDecimation));
00318                 }
00319                 decimatedData.setStereoCameraModel(stereoModel);
00320 
00321                 // compute transform
00322                 t = this->computeTransform(decimatedData, guess, info);
00323 
00324                 // transform back the keypoints in the original image
00325                 std::vector<cv::KeyPoint> kpts = decimatedData.keypoints();
00326                 double log2value = log(double(_imageDecimation))/log(2.0);
00327                 for(unsigned int i=0; i<kpts.size(); ++i)
00328                 {
00329                         kpts[i].pt.x *= _imageDecimation;
00330                         kpts[i].pt.y *= _imageDecimation;
00331                         kpts[i].size *= _imageDecimation;
00332                         kpts[i].octave += log2value;
00333                 }
00334                 data.setFeatures(kpts, decimatedData.descriptors());
00335 
00336                 if(info)
00337                 {
00338                         UASSERT(info->newCorners.size() == info->refCorners.size());
00339                         for(unsigned int i=0; i<info->newCorners.size(); ++i)
00340                         {
00341                                 info->refCorners[i].x *= _imageDecimation;
00342                                 info->refCorners[i].y *= _imageDecimation;
00343                                 info->newCorners[i].x *= _imageDecimation;
00344                                 info->newCorners[i].y *= _imageDecimation;
00345                         }
00346                         for(std::multimap<int, cv::KeyPoint>::iterator iter=info->words.begin(); iter!=info->words.end(); ++iter)
00347                         {
00348                                 iter->second.pt.x *= _imageDecimation;
00349                                 iter->second.pt.y *= _imageDecimation;
00350                                 iter->second.size *= _imageDecimation;
00351                                 iter->second.octave += log2value;
00352                         }
00353                 }
00354         }
00355         else
00356         {
00357                 t = this->computeTransform(data, guess, info);
00358         }
00359 
00360         if(info)
00361         {
00362                 info->timeEstimation = time.ticks();
00363                 info->lost = t.isNull();
00364                 info->stamp = data.stamp();
00365                 info->interval = dt;
00366                 info->transform = t;
00367 
00368                 if(!data.groundTruth().isNull())
00369                 {
00370                         if(!previousGroundTruthPose_.isNull())
00371                         {
00372                                 info->transformGroundTruth = previousGroundTruthPose_.inverse() * data.groundTruth();
00373                         }
00374                         previousGroundTruthPose_ = data.groundTruth();
00375                 }
00376         }
00377 
00378         if(!t.isNull())
00379         {
00380                 _resetCurrentCount = _resetCountdown;
00381 
00382                 float vx,vy,vz, vroll,vpitch,vyaw;
00383                 t.getTranslationAndEulerAngles(vx,vy,vz, vroll,vpitch,vyaw);
00384 
00385                 // transform to velocity
00386                 if(dt)
00387                 {
00388                         vx /= dt;
00389                         vy /= dt;
00390                         vz /= dt;
00391                         vroll /= dt;
00392                         vpitch /= dt;
00393                         vyaw /= dt;
00394                 }
00395 
00396                 if(_force3DoF || !_holonomic || particleFilters_.size() || _filteringStrategy==1)
00397                 {
00398                         if(_filteringStrategy == 1)
00399                         {
00400                                 if(previousVelocityTransform_.isNull())
00401                                 {
00402                                         // reset Kalman
00403                                         if(dt)
00404                                         {
00405                                                 initKalmanFilter(t, vx,vy,vz,vroll,vpitch,vyaw);
00406                                         }
00407                                         else
00408                                         {
00409                                                 initKalmanFilter(t);
00410                                         }
00411                                 }
00412                                 else
00413                                 {
00414                                         // Kalman filtering
00415                                         updateKalmanFilter(vx,vy,vz,vroll,vpitch,vyaw);
00416                                 }
00417                         }
00418                         else if(particleFilters_.size())
00419                         {
00420                                 // Particle filtering
00421                                 UASSERT(particleFilters_.size()==6);
00422                                 if(previousVelocityTransform_.isNull())
00423                                 {
00424                                         particleFilters_[0]->init(vx);
00425                                         particleFilters_[1]->init(vy);
00426                                         particleFilters_[2]->init(vz);
00427                                         particleFilters_[3]->init(vroll);
00428                                         particleFilters_[4]->init(vpitch);
00429                                         particleFilters_[5]->init(vyaw);
00430                                 }
00431                                 else
00432                                 {
00433                                         vx = particleFilters_[0]->filter(vx);
00434                                         vy = particleFilters_[1]->filter(vy);
00435                                         vyaw = particleFilters_[5]->filter(vyaw);
00436 
00437                                         if(!_holonomic)
00438                                         {
00439                                                 // arc trajectory around ICR
00440                                                 float tmpY = vyaw!=0.0f ? vx / tan((CV_PI-vyaw)/2.0f) : 0.0f;
00441                                                 if(fabs(tmpY) < fabs(vy) || (tmpY<=0 && vy >=0) || (tmpY>=0 && vy<=0))
00442                                                 {
00443                                                         vy = tmpY;
00444                                                 }
00445                                                 else
00446                                                 {
00447                                                         vyaw = (atan(vx/vy)*2.0f-CV_PI)*-1;
00448                                                 }
00449                                         }
00450 
00451                                         if(!_force3DoF)
00452                                         {
00453                                                 vz = particleFilters_[2]->filter(vz);
00454                                                 vroll = particleFilters_[3]->filter(vroll);
00455                                                 vpitch = particleFilters_[4]->filter(vpitch);
00456                                         }
00457                                 }
00458 
00459                                 if(info)
00460                                 {
00461                                         info->timeParticleFiltering = time.ticks();
00462                                 }
00463 
00464                                 if(_force3DoF)
00465                                 {
00466                                         vz = 0.0f;
00467                                         vroll = 0.0f;
00468                                         vpitch = 0.0f;
00469                                 }
00470                         }
00471                         else if(!_holonomic)
00472                         {
00473                                 // arc trajectory around ICR
00474                                 vy = vyaw!=0.0f ? vx / tan((CV_PI-vyaw)/2.0f) : 0.0f;
00475                                 if(_force3DoF)
00476                                 {
00477                                         vz = 0.0f;
00478                                         vroll = 0.0f;
00479                                         vpitch = 0.0f;
00480                                 }
00481                         }
00482 
00483                         if(dt)
00484                         {
00485                                 t = Transform(vx*dt, vy*dt, vz*dt, vroll*dt, vpitch*dt, vyaw*dt);
00486                         }
00487                         else
00488                         {
00489                                 t = Transform(vx, vy, vz, vroll, vpitch, vyaw);
00490                         }
00491 
00492                         if(info)
00493                         {
00494                                 info->transformFiltered = t;
00495                         }
00496                 }
00497 
00498                 previousStamp_ = data.stamp();
00499                 previousVelocityTransform_.setNull();
00500                 if(dt)
00501                 {
00502                         previousVelocityTransform_ = Transform(vx, vy, vz, vroll, vpitch, vyaw);
00503                 }
00504 
00505                 if(info)
00506                 {
00507                         distanceTravelled_ += t.getNorm();
00508                         info->distanceTravelled = distanceTravelled_;
00509                 }
00510 
00511                 return _pose *= t; // update
00512         }
00513         else if(_resetCurrentCount > 0)
00514         {
00515                 UWARN("Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", _resetCurrentCount);
00516 
00517                 --_resetCurrentCount;
00518                 if(_resetCurrentCount == 0)
00519                 {
00520                         UWARN("Odometry automatically reset to latest pose!");
00521                         this->reset(_pose);
00522                 }
00523         }
00524 
00525         previousVelocityTransform_.setNull();
00526         previousStamp_ = 0;
00527 
00528         return Transform();
00529 }
00530 
00531 void Odometry::initKalmanFilter(const Transform & initialPose, float vx, float vy, float vz, float vroll, float vpitch, float vyaw)
00532 {
00533         UDEBUG("");
00534         // See OpenCV tutorial: http://docs.opencv.org/master/dc/d2c/tutorial_real_time_pose.html
00535         // See Kalman filter pose/orientation estimation theory: http://campar.in.tum.de/Chair/KalmanFilter
00536 
00537         // initialize the Kalman filter
00538         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'')
00539         int nMeasurements = 6;       // the number of measured states (x',y',z',roll',pitch',yaw')
00540         if(_force3DoF)
00541         {
00542                 nStates = 9;             // the number of states (x,y,x',y',x'',y'',yaw,yaw',yaw'')
00543                 nMeasurements = 3;       // the number of measured states (x',y',yaw')
00544         }
00545         int nInputs = 0;             // the number of action control
00546 
00547         /* From viso2, measurement covariance
00548          * static const boost::array<double, 36> STANDARD_POSE_COVARIANCE =
00549         { { 0.1, 0, 0, 0, 0, 0,
00550             0, 0.1, 0, 0, 0, 0,
00551             0, 0, 0.1, 0, 0, 0,
00552             0, 0, 0, 0.17, 0, 0,
00553             0, 0, 0, 0, 0.17, 0,
00554             0, 0, 0, 0, 0, 0.17 } };
00555         static const boost::array<double, 36> STANDARD_TWIST_COVARIANCE =
00556         { { 0.05, 0, 0, 0, 0, 0,
00557             0, 0.05, 0, 0, 0, 0,
00558             0, 0, 0.05, 0, 0, 0,
00559             0, 0, 0, 0.09, 0, 0,
00560             0, 0, 0, 0, 0.09, 0,
00561             0, 0, 0, 0, 0, 0.09 } };
00562          */
00563 
00564 
00565         kalmanFilter_.init(nStates, nMeasurements, nInputs);                 // init Kalman Filter
00566         cv::setIdentity(kalmanFilter_.processNoiseCov, cv::Scalar::all(_kalmanProcessNoise));  // set process noise
00567         cv::setIdentity(kalmanFilter_.measurementNoiseCov, cv::Scalar::all(_kalmanMeasurementNoise));   // set measurement noise
00568         cv::setIdentity(kalmanFilter_.errorCovPost, cv::Scalar::all(1));             // error covariance
00569 
00570         float x,y,z,roll,pitch,yaw;
00571         initialPose.getTranslationAndEulerAngles(x,y,z,roll,pitch,yaw);
00572 
00573         if(_force3DoF)
00574         {
00575         /* MEASUREMENT MODEL (velocity) */
00576                 //  [0 0 1 0 0 0 0 0 0]
00577                 //  [0 0 0 1 0 0 0 0 0]
00578                 //  [0 0 0 0 0 0 0 1 0]
00579                 kalmanFilter_.measurementMatrix.at<float>(0,2) = 1;  // x'
00580                 kalmanFilter_.measurementMatrix.at<float>(1,3) = 1;  // y'
00581                 kalmanFilter_.measurementMatrix.at<float>(2,7) = 1; // yaw'
00582 
00583                 kalmanFilter_.statePost.at<float>(0) = x;
00584                 kalmanFilter_.statePost.at<float>(1) = y;
00585                 kalmanFilter_.statePost.at<float>(6) = yaw;
00586 
00587                 kalmanFilter_.statePost.at<float>(2) = vx;
00588                 kalmanFilter_.statePost.at<float>(3) = vy;
00589                 kalmanFilter_.statePost.at<float>(7) = vyaw;
00590         }
00591         else
00592         {
00593             /* MEASUREMENT MODEL (velocity) */
00594                 //  [0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
00595                 //  [0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0]
00596                 //  [0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0]
00597                 //  [0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0]
00598                 //  [0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0]
00599                 //  [0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0]
00600                 kalmanFilter_.measurementMatrix.at<float>(0,3) = 1;  // x'
00601                 kalmanFilter_.measurementMatrix.at<float>(1,4) = 1;  // y'
00602                 kalmanFilter_.measurementMatrix.at<float>(2,5) = 1;  // z'
00603                 kalmanFilter_.measurementMatrix.at<float>(3,12) = 1; // roll'
00604                 kalmanFilter_.measurementMatrix.at<float>(4,13) = 1; // pitch'
00605                 kalmanFilter_.measurementMatrix.at<float>(5,14) = 1; // yaw'
00606 
00607                 kalmanFilter_.statePost.at<float>(0) = x;
00608                 kalmanFilter_.statePost.at<float>(1) = y;
00609                 kalmanFilter_.statePost.at<float>(2) = z;
00610                 kalmanFilter_.statePost.at<float>(9) = roll;
00611                 kalmanFilter_.statePost.at<float>(10) = pitch;
00612                 kalmanFilter_.statePost.at<float>(11) = yaw;
00613 
00614                 kalmanFilter_.statePost.at<float>(3) = vx;
00615                 kalmanFilter_.statePost.at<float>(4) = vy;
00616                 kalmanFilter_.statePost.at<float>(5) = vz;
00617                 kalmanFilter_.statePost.at<float>(12) = vroll;
00618                 kalmanFilter_.statePost.at<float>(13) = vpitch;
00619                 kalmanFilter_.statePost.at<float>(14) = vyaw;
00620         }
00621 }
00622 
00623 void Odometry::predictKalmanFilter(float dt, float * vx, float * vy, float * vz, float * vroll, float * vpitch, float * vyaw)
00624 {
00625         // Set transition matrix with current dt
00626         if(_force3DoF)
00627         {
00628                 // 2D:
00629                 //  [1 0 dt  0 dt2    0   0    0     0] x
00630                 //  [0 1  0 dt   0  dt2   0    0     0] y
00631                 //  [0 0  1  0   dt   0   0    0     0] x'
00632                 //  [0 0  0  1   0   dt   0    0     0] y'
00633                 //  [0 0  0  0   1    0   0    0     0] x''
00634                 //  [0 0  0  0   0    0   0    0     0] y''
00635                 //  [0 0  0  0   0    0   1   dt   dt2] yaw
00636                 //  [0 0  0  0   0    0   0    1    dt] yaw'
00637                 //  [0 0  0  0   0    0   0    0     1] yaw''
00638                 kalmanFilter_.transitionMatrix.at<float>(0,2) = dt;
00639                 kalmanFilter_.transitionMatrix.at<float>(1,3) = dt;
00640                 kalmanFilter_.transitionMatrix.at<float>(2,4) = dt;
00641                 kalmanFilter_.transitionMatrix.at<float>(3,5) = dt;
00642                 kalmanFilter_.transitionMatrix.at<float>(0,4) = 0.5*pow(dt,2);
00643                 kalmanFilter_.transitionMatrix.at<float>(1,5) = 0.5*pow(dt,2);
00644                 // orientation
00645                 kalmanFilter_.transitionMatrix.at<float>(6,7) = dt;
00646                 kalmanFilter_.transitionMatrix.at<float>(7,8) = dt;
00647                 kalmanFilter_.transitionMatrix.at<float>(6,8) = 0.5*pow(dt,2);
00648         }
00649         else
00650         {
00651                 //  [1 0 0 dt  0  0 dt2   0   0 0 0 0  0  0  0   0   0   0] x
00652                 //  [0 1 0  0 dt  0   0 dt2   0 0 0 0  0  0  0   0   0   0] y
00653                 //  [0 0 1  0  0 dt   0   0 dt2 0 0 0  0  0  0   0   0   0] z
00654                 //  [0 0 0  1  0  0  dt   0   0 0 0 0  0  0  0   0   0   0] x'
00655                 //  [0 0 0  0  1  0   0  dt   0 0 0 0  0  0  0   0   0   0] y'
00656                 //  [0 0 0  0  0  1   0   0  dt 0 0 0  0  0  0   0   0   0] z'
00657                 //  [0 0 0  0  0  0   1   0   0 0 0 0  0  0  0   0   0   0] x''
00658                 //  [0 0 0  0  0  0   0   1   0 0 0 0  0  0  0   0   0   0] y''
00659                 //  [0 0 0  0  0  0   0   0   1 0 0 0  0  0  0   0   0   0] z''
00660                 //  [0 0 0  0  0  0   0   0   0 1 0 0 dt  0  0 dt2   0   0]
00661                 //  [0 0 0  0  0  0   0   0   0 0 1 0  0 dt  0   0 dt2   0]
00662                 //  [0 0 0  0  0  0   0   0   0 0 0 1  0  0 dt   0   0 dt2]
00663                 //  [0 0 0  0  0  0   0   0   0 0 0 0  1  0  0  dt   0   0]
00664                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  1  0   0  dt   0]
00665                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  1   0   0  dt]
00666                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  0   1   0   0]
00667                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  0   0   1   0]
00668                 //  [0 0 0  0  0  0   0   0   0 0 0 0  0  0  0   0   0   1]
00669                 // position
00670                 kalmanFilter_.transitionMatrix.at<float>(0,3) = dt;
00671                 kalmanFilter_.transitionMatrix.at<float>(1,4) = dt;
00672                 kalmanFilter_.transitionMatrix.at<float>(2,5) = dt;
00673                 kalmanFilter_.transitionMatrix.at<float>(3,6) = dt;
00674                 kalmanFilter_.transitionMatrix.at<float>(4,7) = dt;
00675                 kalmanFilter_.transitionMatrix.at<float>(5,8) = dt;
00676                 kalmanFilter_.transitionMatrix.at<float>(0,6) = 0.5*pow(dt,2);
00677                 kalmanFilter_.transitionMatrix.at<float>(1,7) = 0.5*pow(dt,2);
00678                 kalmanFilter_.transitionMatrix.at<float>(2,8) = 0.5*pow(dt,2);
00679                 // orientation
00680                 kalmanFilter_.transitionMatrix.at<float>(9,12) = dt;
00681                 kalmanFilter_.transitionMatrix.at<float>(10,13) = dt;
00682                 kalmanFilter_.transitionMatrix.at<float>(11,14) = dt;
00683                 kalmanFilter_.transitionMatrix.at<float>(12,15) = dt;
00684                 kalmanFilter_.transitionMatrix.at<float>(13,16) = dt;
00685                 kalmanFilter_.transitionMatrix.at<float>(14,17) = dt;
00686                 kalmanFilter_.transitionMatrix.at<float>(9,15) = 0.5*pow(dt,2);
00687                 kalmanFilter_.transitionMatrix.at<float>(10,16) = 0.5*pow(dt,2);
00688                 kalmanFilter_.transitionMatrix.at<float>(11,17) = 0.5*pow(dt,2);
00689         }
00690 
00691         // First predict, to update the internal statePre variable
00692         UDEBUG("Predict");
00693         const cv::Mat & prediction = kalmanFilter_.predict();
00694 
00695         if(vx)
00696                 *vx = prediction.at<float>(3);                      // x'
00697         if(vy)
00698                 *vy = prediction.at<float>(4);                      // y'
00699         if(vz)
00700                 *vz = _force3DoF?0.0f:prediction.at<float>(5);      // z'
00701         if(vroll)
00702                 *vroll = _force3DoF?0.0f:prediction.at<float>(12);  // roll'
00703         if(vpitch)
00704                 *vpitch = _force3DoF?0.0f:prediction.at<float>(13); // pitch'
00705         if(vyaw)
00706                 *vyaw = prediction.at<float>(_force3DoF?7:14);      // yaw'
00707 }
00708 
00709 void Odometry::updateKalmanFilter(float & vx, float & vy, float & vz, float & vroll, float & vpitch, float & vyaw)
00710 {
00711         // Set measurement to predict
00712         cv::Mat measurements;
00713         if(!_force3DoF)
00714         {
00715                 measurements = cv::Mat(6,1,CV_32FC1);
00716                 measurements.at<float>(0) = vx;     // x'
00717                 measurements.at<float>(1) = vy;     // y'
00718                 measurements.at<float>(2) = vz;     // z'
00719                 measurements.at<float>(3) = vroll;  // roll'
00720                 measurements.at<float>(4) = vpitch; // pitch'
00721                 measurements.at<float>(5) = vyaw;   // yaw'
00722         }
00723         else
00724         {
00725                 measurements = cv::Mat(3,1,CV_32FC1);
00726                 measurements.at<float>(0) = vx;     // x'
00727                 measurements.at<float>(1) = vy;     // y'
00728                 measurements.at<float>(2) = vyaw;   // yaw',
00729         }
00730 
00731         // The "correct" phase that is going to use the predicted value and our measurement
00732         UDEBUG("Correct");
00733         const cv::Mat & estimated = kalmanFilter_.correct(measurements);
00734 
00735 
00736         vx = estimated.at<float>(3);                      // x'
00737         vy = estimated.at<float>(4);                      // y'
00738         vz = _force3DoF?0.0f:estimated.at<float>(5);      // z'
00739         vroll = _force3DoF?0.0f:estimated.at<float>(12);  // roll'
00740         vpitch = _force3DoF?0.0f:estimated.at<float>(13); // pitch'
00741         vyaw = estimated.at<float>(_force3DoF?7:14);      // yaw'
00742 }
00743 
00744 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17