Odometry.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, 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/Odometry.h"
00029 #include "rtabmap/core/OdometryInfo.h"
00030 #include "rtabmap/utilite/ULogger.h"
00031 #include "rtabmap/utilite/UTimer.h"
00032 
00033 namespace rtabmap {
00034 
00035 Odometry::Odometry(const rtabmap::ParametersMap & parameters) :
00036                 _roiRatios(Parameters::defaultOdomRoiRatios()),
00037                 _minInliers(Parameters::defaultOdomMinInliers()),
00038                 _inlierDistance(Parameters::defaultOdomInlierDistance()),
00039                 _iterations(Parameters::defaultOdomIterations()),
00040                 _refineIterations(Parameters::defaultOdomRefineIterations()),
00041                 _maxDepth(Parameters::defaultOdomMaxDepth()),
00042                 _resetCountdown(Parameters::defaultOdomResetCountdown()),
00043                 _force2D(Parameters::defaultOdomForce2D()),
00044                 _fillInfoData(Parameters::defaultOdomFillInfoData()),
00045                 _pnpEstimation(Parameters::defaultOdomPnPEstimation()),
00046                 _pnpReprojError(Parameters::defaultOdomPnPReprojError()),
00047                 _pnpFlags(Parameters::defaultOdomPnPFlags()),
00048                 _resetCurrentCount(0)
00049 {
00050         Parameters::parse(parameters, Parameters::kOdomResetCountdown(), _resetCountdown);
00051         Parameters::parse(parameters, Parameters::kOdomMinInliers(), _minInliers);
00052         Parameters::parse(parameters, Parameters::kOdomInlierDistance(), _inlierDistance);
00053         Parameters::parse(parameters, Parameters::kOdomIterations(), _iterations);
00054         Parameters::parse(parameters, Parameters::kOdomRefineIterations(), _refineIterations);
00055         Parameters::parse(parameters, Parameters::kOdomMaxDepth(), _maxDepth);
00056         Parameters::parse(parameters, Parameters::kOdomRoiRatios(), _roiRatios);
00057         Parameters::parse(parameters, Parameters::kOdomForce2D(), _force2D);
00058         Parameters::parse(parameters, Parameters::kOdomFillInfoData(), _fillInfoData);
00059         Parameters::parse(parameters, Parameters::kOdomPnPEstimation(), _pnpEstimation);
00060         Parameters::parse(parameters, Parameters::kOdomPnPReprojError(), _pnpReprojError);
00061         Parameters::parse(parameters, Parameters::kOdomPnPFlags(), _pnpFlags);
00062         UASSERT(_pnpFlags>=0 && _pnpFlags <=2);
00063 }
00064 
00065 void Odometry::reset(const Transform & initialPose)
00066 {
00067         _resetCurrentCount = 0;
00068         if(_force2D)
00069         {
00070                 float x,y,z, roll,pitch,yaw;
00071                 initialPose.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
00072                 if(z != 0.0f || roll != 0.0f || yaw != 0.0f)
00073                 {
00074                         UWARN("Force2D=true and the initial pose contains z, roll or pitch values (%s). They are set to null.", initialPose.prettyPrint().c_str());
00075                 }
00076                 Transform pose(x, y, 0, 0, 0, yaw);
00077                 _pose = pose;
00078         }
00079         else
00080         {
00081                 _pose = initialPose;
00082         }
00083 }
00084 
00085 Transform Odometry::process(const SensorData & data, OdometryInfo * info)
00086 {
00087         if(_pose.isNull())
00088         {
00089                 _pose.setIdentity(); // initialized
00090         }
00091 
00092         UASSERT(!data.image().empty());
00093         if(dynamic_cast<OdometryMono*>(this) == 0)
00094         {
00095                 UASSERT(!data.depthOrRightImage().empty());
00096         }
00097 
00098         if(data.fx() <= 0 || data.fyOrBaseline() <= 0)
00099         {
00100                 UERROR("Rectified images required! Calibrate your camera. (fx=%f, fy/baseline=%f, cx=%f, cy=%f)",
00101                                 data.fx(), data.fyOrBaseline(), data.cx(), data.cy());
00102                 return Transform();
00103         }
00104 
00105         UTimer time;
00106         Transform t = this->computeTransform(data, info);
00107 
00108         if(info)
00109         {
00110                 info->time = time.elapsed();
00111                 info->lost = t.isNull();
00112         }
00113 
00114         if(!t.isNull())
00115         {
00116                 _resetCurrentCount = _resetCountdown;
00117 
00118                 if(_force2D)
00119                 {
00120                         float x,y,z, roll,pitch,yaw;
00121                         t.getTranslationAndEulerAngles(x, y, z, roll, pitch, yaw);
00122                         t = Transform(x,y,0, 0,0,yaw);
00123                 }
00124 
00125                 return _pose *= t; // updated
00126         }
00127         else if(_resetCurrentCount > 0)
00128         {
00129                 UWARN("Odometry lost! Odometry will be reset after next %d consecutive unsuccessful odometry updates...", _resetCurrentCount);
00130 
00131                 --_resetCurrentCount;
00132                 if(_resetCurrentCount == 0)
00133                 {
00134                         UWARN("Odometry automatically reset to latest pose!");
00135                         this->reset(_pose);
00136                 }
00137         }
00138 
00139         return Transform();
00140 }
00141 
00142 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32