util3d_mapping.h
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 #ifndef UTIL3D_MAPPING_H_
00029 #define UTIL3D_MAPPING_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h"
00032 
00033 #include <opencv2/core/core.hpp>
00034 #include <map>
00035 #include <rtabmap/core/Transform.h>
00036 #include <pcl/pcl_base.h>
00037 #include <pcl/point_cloud.h>
00038 #include <pcl/point_types.h>
00039 
00040 namespace rtabmap
00041 {
00042 
00043 namespace util3d
00044 {
00045 
00046 void RTABMAP_EXP occupancy2DFromLaserScan(
00047                 const cv::Mat & scan,
00048                 cv::Mat & ground,
00049                 cv::Mat & obstacles,
00050                 float cellSize,
00051                 bool unknownSpaceFilled = false,
00052                 float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
00053 
00054 cv::Mat RTABMAP_EXP create2DMapFromOccupancyLocalMaps(
00055                 const std::map<int, Transform> & poses,
00056                 const std::map<int, std::pair<cv::Mat, cv::Mat> > & occupancy,
00057                 float cellSize,
00058                 float & xMin,
00059                 float & yMin,
00060                 float minMapSize = 0.0f,
00061                 bool erode = false);
00062 
00063 cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
00064                 const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans,
00065                 float cellSize,
00066                 bool unknownSpaceFilled,
00067                 float & xMin,
00068                 float & yMin,
00069                 float minMapSize = 0.0f,
00070                 float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
00071 
00072 void RTABMAP_EXP rayTrace(const cv::Point2i & start,
00073                 const cv::Point2i & end,
00074                 cv::Mat & grid,
00075                 bool stopOnObstacle);
00076 
00077 cv::Mat RTABMAP_EXP convertMap2Image8U(const cv::Mat & map8S);
00078 
00079 template<typename PointT>
00080 typename pcl::PointCloud<PointT>::Ptr projectCloudOnXYPlane(
00081                 const typename pcl::PointCloud<PointT> & cloud);
00082 
00083 // templated methods
00084 template<typename PointT>
00085 void segmentObstaclesFromGround(
00086                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00087                 const pcl::IndicesPtr & indices,
00088                 pcl::IndicesPtr & ground,
00089                 pcl::IndicesPtr & obstacles,
00090                 int normalKSearch,
00091                 float groundNormalAngle,
00092                 float clusterRadius,
00093                 int minClusterSize,
00094                 bool segmentFlatObstacles = false,
00095                 float maxGroundHeight = 0.0f,
00096                 pcl::IndicesPtr * flatObstacles = 0,
00097                 const Eigen::Vector4f & viewPoint = Eigen::Vector4f(0,0,100,0));
00098 template<typename PointT>
00099 void segmentObstaclesFromGround(
00100                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00101                 pcl::IndicesPtr & ground,
00102                 pcl::IndicesPtr & obstacles,
00103                 int normalKSearch,
00104                 float groundNormalAngle,
00105                 float clusterRadius,
00106                 int minClusterSize,
00107                 bool segmentFlatObstacles = false,
00108                 float maxGroundHeight = 0.0f,
00109                 pcl::IndicesPtr * flatObstacles = 0,
00110                 const Eigen::Vector4f & viewPoint = Eigen::Vector4f(0,0,100,0));
00111 
00112 template<typename PointT>
00113 void occupancy2DFromGroundObstacles(
00114                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00115                 const pcl::IndicesPtr & groundIndices,
00116                 const pcl::IndicesPtr & obstaclesIndices,
00117                 cv::Mat & ground,
00118                 cv::Mat & obstacles,
00119                 float cellSize);
00120 
00121 template<typename PointT>
00122 void occupancy2DFromGroundObstacles(
00123                 const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
00124                 const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
00125                 cv::Mat & ground,
00126                 cv::Mat & obstacles,
00127                 float cellSize);
00128 
00129 template<typename PointT>
00130 void occupancy2DFromCloud3D(
00131                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00132                 cv::Mat & ground,
00133                 cv::Mat & obstacles,
00134                 float cellSize = 0.05f,
00135                 float groundNormalAngle = M_PI_4,
00136                 int minClusterSize = 20,
00137                 bool segmentFlatObstacles = false,
00138                 float maxGroundHeight = 0.0f);
00139 template<typename PointT>
00140 void occupancy2DFromCloud3D(
00141                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00142                 const pcl::IndicesPtr & indices,
00143                 cv::Mat & ground,
00144                 cv::Mat & obstacles,
00145                 float cellSize = 0.05f,
00146                 float groundNormalAngle = M_PI_4,
00147                 int minClusterSize = 20,
00148                 bool segmentFlatObstacles = false,
00149                 float maxGroundHeight = 0.0f);
00150 
00151 } // namespace util3d
00152 } // namespace rtabmap
00153 
00154 #include "rtabmap/core/impl/util3d_mapping.hpp"
00155 
00156 #endif /* UTIL3D_MAPPING_H_ */


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