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 RTABMAP_DEPRECATED(void RTABMAP_EXP occupancy2DFromLaserScan(
00047                 const cv::Mat & scan, // in /base_link frame
00048                 cv::Mat & empty,
00049                 cv::Mat & occupied,
00050                 float cellSize,
00051                 bool unknownSpaceFilled = false,
00052                 float scanMaxRange = 0.0f), "Use interface with \"viewpoint\" parameter to make sure the ray tracing origin is from the sensor and not the base.");
00053 
00054 RTABMAP_DEPRECATED(void RTABMAP_EXP occupancy2DFromLaserScan(
00055                 const cv::Mat & scan, // in /base_link frame
00056                 const cv::Point3f & viewpoint, // /base_link -> /base_scan
00057                 cv::Mat & empty,
00058                 cv::Mat & occupied,
00059                 float cellSize,
00060                 bool unknownSpaceFilled = false,
00061                 float scanMaxRange = 0.0f), "Use interface with scanHit/scanNoHit parameters: scanNoHit set to null matrix has the same functionality than this method.");
00062 
00063 void RTABMAP_EXP occupancy2DFromLaserScan(
00064                 const cv::Mat & scanHit, // in /base_link frame
00065                 const cv::Mat & scanNoHit, // in /base_link frame
00066                 const cv::Point3f & viewpoint, // /base_link -> /base_scan
00067                 cv::Mat & empty,
00068                 cv::Mat & occupied,
00069                 float cellSize,
00070                 bool unknownSpaceFilled = false,
00071                 float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
00072 
00073 cv::Mat RTABMAP_EXP create2DMapFromOccupancyLocalMaps(
00074                 const std::map<int, Transform> & poses,
00075                 const std::map<int, std::pair<cv::Mat, cv::Mat> > & occupancy,
00076                 float cellSize,
00077                 float & xMin,
00078                 float & yMin,
00079                 float minMapSize = 0.0f,
00080                 bool erode = false,
00081                 float footprintRadius = 0.0f);
00082 
00083 RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
00084                 const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans, // in /base_link frame
00085                 float cellSize,
00086                 bool unknownSpaceFilled,
00087                 float & xMin,
00088                 float & yMin,
00089                 float minMapSize = 0.0f,
00090                 float scanMaxRange = 0.0f), "Use interface with \"viewpoints\" parameter to make sure the ray tracing origin is from the sensor and not the base.");
00091 
00092 RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
00093                 const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans, // in /base_link frame
00094                 const std::map<int, cv::Point3f > & viewpoints, // /base_link -> /base_scan
00095                 float cellSize,
00096                 bool unknownSpaceFilled,
00097                 float & xMin,
00098                 float & yMin,
00099                 float minMapSize = 0.0f,
00100                 float scanMaxRange = 0.0f), "Use interface with cv::Mat scans.");
00101 
00102 cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
00103                 const std::map<int, std::pair<cv::Mat, cv::Mat> > & scans, // <id, <hit, no hit> >, in /base_link frame
00104                 const std::map<int, cv::Point3f > & viewpoints, // /base_link -> /base_scan
00105                 float cellSize,
00106                 bool unknownSpaceFilled,
00107                 float & xMin,
00108                 float & yMin,
00109                 float minMapSize = 0.0f,
00110                 float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
00111 
00112 void RTABMAP_EXP rayTrace(const cv::Point2i & start,
00113                 const cv::Point2i & end,
00114                 cv::Mat & grid,
00115                 bool stopOnObstacle);
00116 
00117 cv::Mat RTABMAP_EXP convertMap2Image8U(const cv::Mat & map8S, bool pgmFormat = false);
00118 cv::Mat RTABMAP_EXP convertImage8U2Map(const cv::Mat & map8U, bool pgmFormat = false);
00119 
00120 cv::Mat RTABMAP_EXP erodeMap(const cv::Mat & map);
00121 
00122 template<typename PointT>
00123 typename pcl::PointCloud<PointT>::Ptr projectCloudOnXYPlane(
00124                 const typename pcl::PointCloud<PointT> & cloud);
00125 
00126 // templated methods
00127 template<typename PointT>
00128 void segmentObstaclesFromGround(
00129                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00130                 const pcl::IndicesPtr & indices,
00131                 pcl::IndicesPtr & ground,
00132                 pcl::IndicesPtr & obstacles,
00133                 int normalKSearch,
00134                 float groundNormalAngle,
00135                 float clusterRadius,
00136                 int minClusterSize,
00137                 bool segmentFlatObstacles = false,
00138                 float maxGroundHeight = 0.0f,
00139                 pcl::IndicesPtr * flatObstacles = 0,
00140                 const Eigen::Vector4f & viewPoint = Eigen::Vector4f(0,0,100,0));
00141 template<typename PointT>
00142 void segmentObstaclesFromGround(
00143                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00144                 pcl::IndicesPtr & ground,
00145                 pcl::IndicesPtr & obstacles,
00146                 int normalKSearch,
00147                 float groundNormalAngle,
00148                 float clusterRadius,
00149                 int minClusterSize,
00150                 bool segmentFlatObstacles = false,
00151                 float maxGroundHeight = 0.0f,
00152                 pcl::IndicesPtr * flatObstacles = 0,
00153                 const Eigen::Vector4f & viewPoint = Eigen::Vector4f(0,0,100,0));
00154 
00155 template<typename PointT>
00156 void occupancy2DFromGroundObstacles(
00157                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00158                 const pcl::IndicesPtr & groundIndices,
00159                 const pcl::IndicesPtr & obstaclesIndices,
00160                 cv::Mat & ground,
00161                 cv::Mat & obstacles,
00162                 float cellSize);
00163 
00164 template<typename PointT>
00165 void occupancy2DFromGroundObstacles(
00166                 const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
00167                 const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
00168                 cv::Mat & ground,
00169                 cv::Mat & obstacles,
00170                 float cellSize);
00171 
00172 template<typename PointT>
00173 void occupancy2DFromCloud3D(
00174                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00175                 cv::Mat & ground,
00176                 cv::Mat & obstacles,
00177                 float cellSize = 0.05f,
00178                 float groundNormalAngle = M_PI_4,
00179                 int minClusterSize = 20,
00180                 bool segmentFlatObstacles = false,
00181                 float maxGroundHeight = 0.0f);
00182 template<typename PointT>
00183 void occupancy2DFromCloud3D(
00184                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00185                 const pcl::IndicesPtr & indices,
00186                 cv::Mat & ground,
00187                 cv::Mat & obstacles,
00188                 float cellSize = 0.05f,
00189                 float groundNormalAngle = M_PI_4,
00190                 int minClusterSize = 20,
00191                 bool segmentFlatObstacles = false,
00192                 float maxGroundHeight = 0.0f);
00193 
00194 } // namespace util3d
00195 } // namespace rtabmap
00196 
00197 #include "rtabmap/core/impl/util3d_mapping.hpp"
00198 
00199 #endif /* UTIL3D_MAPPING_H_ */


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