OdometryICP.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/util3d.h"
00030 #include "rtabmap/core/OdometryInfo.h"
00031 #include "rtabmap/utilite/ULogger.h"
00032 #include "rtabmap/utilite/UTimer.h"
00033 
00034 namespace rtabmap {
00035 
00036 OdometryICP::OdometryICP(int decimation,
00037                 float voxelSize,
00038                 int samples,
00039                 float maxCorrespondenceDistance,
00040                 int maxIterations,
00041                 float correspondenceRatio,
00042                 bool pointToPlane,
00043                 const ParametersMap & odometryParameter) :
00044         Odometry(odometryParameter),
00045         _decimation(decimation),
00046         _voxelSize(voxelSize),
00047         _samples(samples),
00048         _maxCorrespondenceDistance(maxCorrespondenceDistance),
00049         _maxIterations(maxIterations),
00050         _correspondenceRatio(correspondenceRatio),
00051         _pointToPlane(pointToPlane),
00052         _previousCloudNormal(new pcl::PointCloud<pcl::PointNormal>),
00053         _previousCloud(new pcl::PointCloud<pcl::PointXYZ>)
00054 {
00055 }
00056 
00057 void OdometryICP::reset(const Transform & initialPose)
00058 {
00059         Odometry::reset(initialPose);
00060         _previousCloudNormal.reset(new pcl::PointCloud<pcl::PointNormal>);
00061         _previousCloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
00062 }
00063 
00064 // return not null transform if odometry is correctly computed
00065 Transform OdometryICP::computeTransform(const SensorData & data, OdometryInfo * info)
00066 {
00067         UTimer timer;
00068         Transform output;
00069 
00070         bool hasConverged = false;
00071         double variance = 0;
00072         unsigned int minPoints = 100;
00073         if(!data.depth().empty())
00074         {
00075                 if(data.depth().type() == CV_8UC1)
00076                 {
00077                         UERROR("ICP 3D cannot be done on stereo images!");
00078                         return output;
00079                 }
00080 
00081                 pcl::PointCloud<pcl::PointXYZ>::Ptr newCloudXYZ = util3d::getICPReadyCloud(
00082                                                 data.depth(),
00083                                                 data.fx(),
00084                                                 data.fy(),
00085                                                 data.cx(),
00086                                                 data.cy(),
00087                                                 _decimation,
00088                                                 this->getMaxDepth(),
00089                                                 _voxelSize,
00090                                                 _samples,
00091                                                 data.localTransform());
00092 
00093                 if(_pointToPlane)
00094                 {
00095                         pcl::PointCloud<pcl::PointNormal>::Ptr newCloud = util3d::computeNormals(newCloudXYZ);
00096 
00097                         std::vector<int> indices;
00098                         newCloud = util3d::removeNaNNormalsFromPointCloud<pcl::PointNormal>(newCloud);
00099                         if(newCloudXYZ->size() != newCloud->size())
00100                         {
00101                                 UWARN("removed nan normals...");
00102                         }
00103 
00104                         if(_previousCloudNormal->size() > minPoints && newCloud->size() > minPoints)
00105                         {
00106                                 int correspondences = 0;
00107                                 Transform transform = util3d::icpPointToPlane(newCloud,
00108                                                 _previousCloudNormal,
00109                                                 _maxCorrespondenceDistance,
00110                                                 _maxIterations,
00111                                                 &hasConverged,
00112                                                 &variance,
00113                                                 &correspondences);
00114 
00115                                 // verify if there are enough correspondences
00116                                 float correspondencesRatio = float(correspondences)/float(_previousCloudNormal->size()>newCloud->size()?_previousCloudNormal->size():newCloud->size());
00117 
00118                                 if(!transform.isNull() && hasConverged &&
00119                                    correspondencesRatio >= _correspondenceRatio)
00120                                 {
00121                                         output = transform;
00122                                         _previousCloudNormal = newCloud;
00123                                 }
00124                                 else
00125                                 {
00126                                         UWARN("Transform not valid (hasConverged=%s variance = %f)",
00127                                                         hasConverged?"true":"false", variance);
00128                                 }
00129                         }
00130                         else if(newCloud->size() > minPoints)
00131                         {
00132                                 output.setIdentity();
00133                                 _previousCloudNormal = newCloud;
00134                         }
00135                 }
00136                 else
00137                 {
00138                         //point to point
00139                         if(_previousCloud->size() > minPoints && newCloudXYZ->size() > minPoints)
00140                         {
00141                                 int correspondences = 0;
00142                                 Transform transform = util3d::icp(newCloudXYZ,
00143                                                 _previousCloud,
00144                                                 _maxCorrespondenceDistance,
00145                                                 _maxIterations,
00146                                                 &hasConverged,
00147                                                 &variance,
00148                                                 &correspondences);
00149 
00150                                 // verify if there are enough correspondences
00151                                 float correspondencesRatio = float(correspondences)/float(_previousCloud->size()>newCloudXYZ->size()?_previousCloud->size():newCloudXYZ->size());
00152 
00153                                 if(!transform.isNull() && hasConverged &&
00154                                    correspondencesRatio >= _correspondenceRatio)
00155                                 {
00156                                         output = transform;
00157                                         _previousCloud = newCloudXYZ;
00158                                 }
00159                                 else
00160                                 {
00161                                         UWARN("Transform not valid (hasConverged=%s variance = %f)",
00162                                                         hasConverged?"true":"false", variance);
00163                                 }
00164                         }
00165                         else if(newCloudXYZ->size() > minPoints)
00166                         {
00167                                 output.setIdentity();
00168                                 _previousCloud = newCloudXYZ;
00169                         }
00170                 }
00171         }
00172         else
00173         {
00174                 UERROR("Depth is empty?!?");
00175         }
00176 
00177         if(info)
00178         {
00179                 info->variance = variance;
00180         }
00181 
00182         UINFO("Odom update time = %fs hasConverged=%s variance=%f cloud=%d",
00183                         timer.elapsed(),
00184                         hasConverged?"true":"false",
00185                         variance,
00186                         (int)(_pointToPlane?_previousCloudNormal->size():_previousCloud->size()));
00187 
00188         return output;
00189 }
00190 
00191 } // namespace rtabmap


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