LocalGridMaker.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2023, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef SRC_LOCAL_MAP_H_
29 #define SRC_LOCAL_MAP_H_
30 
31 #include "rtabmap/core/rtabmap_core_export.h" // DLL export/import defines
32 
33 #include <pcl/pcl_base.h>
34 #include <pcl/point_types.h>
35 
36 #include <rtabmap/core/Transform.h>
38 #include <rtabmap/core/Signature.h>
39 
40 namespace rtabmap {
41 
42 class RTABMAP_CORE_EXPORT LocalGridMaker
43 {
44 public:
45  LocalGridMaker(const ParametersMap & parameters = ParametersMap());
46  virtual ~LocalGridMaker();
47  virtual void parseParameters(const ParametersMap & parameters);
48 
49  float getCellSize() const {return cellSize_;}
50  bool isGridFromDepth() const {return occupancySensor_;}
51  bool isMapFrameProjection() const {return projMapFrame_;}
52 
53  template<typename PointT>
54  typename pcl::PointCloud<PointT>::Ptr segmentCloud(
55  const typename pcl::PointCloud<PointT>::Ptr & cloud,
56  const pcl::IndicesPtr & indices,
57  const Transform & pose,
58  const cv::Point3f & viewPoint,
59  pcl::IndicesPtr & groundIndices, // output cloud indices
60  pcl::IndicesPtr & obstaclesIndices, // output cloud indices
61  pcl::IndicesPtr * flatObstacles = 0) const; // output cloud indices
62 
63  void createLocalMap(
64  const Signature & node,
65  cv::Mat & groundCells,
66  cv::Mat & obstacleCells,
67  cv::Mat & emptyCells,
68  cv::Point3f & viewPoint);
69 
70  void createLocalMap(
71  const LaserScan & cloud,
72  const Transform & pose,
73  cv::Mat & groundCells,
74  cv::Mat & obstacleCells,
75  cv::Mat & emptyCells,
76  cv::Point3f & viewPointInOut) const;
77 
78 protected:
80 
81  unsigned int cloudDecimation_;
82  float rangeMax_;
83  float rangeMin_;
84  std::vector<float> roiRatios_;
89  float cellSize_;
103  bool grid3D_;
109 };
110 
111 } /* namespace rtabmap */
112 
114 
115 #endif /* SRC_MAP_H_ */
rtabmap::LocalGridMaker::maxGroundHeight_
float maxGroundHeight_
Definition: LocalGridMaker.h:101
rtabmap::LocalGridMaker::groundIsObstacle_
bool groundIsObstacle_
Definition: LocalGridMaker.h:104
rtabmap::LocalGridMaker::noiseFilteringRadius_
float noiseFilteringRadius_
Definition: LocalGridMaker.h:105
rtabmap::LocalGridMaker::roiRatios_
std::vector< float > roiRatios_
Definition: LocalGridMaker.h:84
rtabmap::LocalGridMaker::rangeMax_
float rangeMax_
Definition: LocalGridMaker.h:82
rtabmap::LocalGridMaker::grid3D_
bool grid3D_
Definition: LocalGridMaker.h:103
rtabmap::LocalGridMaker::rangeMin_
float rangeMin_
Definition: LocalGridMaker.h:83
rtabmap::LocalGridMaker::normalKSearch_
int normalKSearch_
Definition: LocalGridMaker.h:94
Transform.h
rtabmap::LocalGridMaker::footprintHeight_
float footprintHeight_
Definition: LocalGridMaker.h:87
rtabmap::LaserScan
Definition: LaserScan.h:37
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
Parameters.h
rtabmap::LocalGridMaker::getCellSize
float getCellSize() const
Definition: LocalGridMaker.h:49
rtabmap::LocalGridMaker::cloudDecimation_
unsigned int cloudDecimation_
Definition: LocalGridMaker.h:81
rtabmap::LocalGridMaker::minClusterSize_
int minClusterSize_
Definition: LocalGridMaker.h:98
rtabmap::LocalGridMaker::maxObstacleHeight_
float maxObstacleHeight_
Definition: LocalGridMaker.h:93
rtabmap::LocalGridMaker::noiseFilteringMinNeighbors_
int noiseFilteringMinNeighbors_
Definition: LocalGridMaker.h:106
rtabmap::LocalGridMaker::normalsSegmentation_
bool normalsSegmentation_
Definition: LocalGridMaker.h:102
rtabmap::LocalGridMaker
Definition: LocalGridMaker.h:42
Signature.h
rtabmap::LocalGridMaker::footprintWidth_
float footprintWidth_
Definition: LocalGridMaker.h:86
rtabmap::LocalGridMaker::rayTracing_
bool rayTracing_
Definition: LocalGridMaker.h:108
rtabmap::LocalGridMaker::maxGroundAngle_
float maxGroundAngle_
Definition: LocalGridMaker.h:96
rtabmap::LocalGridMaker::occupancySensor_
int occupancySensor_
Definition: LocalGridMaker.h:91
rtabmap::LocalGridMaker::minGroundHeight_
float minGroundHeight_
Definition: LocalGridMaker.h:100
rtabmap::Transform
Definition: Transform.h:41
rtabmap::LocalGridMaker::scan2dUnknownSpaceFilled_
bool scan2dUnknownSpaceFilled_
Definition: LocalGridMaker.h:107
rtabmap::LocalGridMaker::groundNormalsUp_
float groundNormalsUp_
Definition: LocalGridMaker.h:95
LocalMapMaker.hpp
rtabmap::LocalGridMaker::clusterRadius_
float clusterRadius_
Definition: LocalGridMaker.h:97
rtabmap::LocalGridMaker::footprintLength_
float footprintLength_
Definition: LocalGridMaker.h:85
rtabmap::LocalGridMaker::preVoxelFiltering_
bool preVoxelFiltering_
Definition: LocalGridMaker.h:90
rtabmap::LocalGridMaker::cellSize_
float cellSize_
Definition: LocalGridMaker.h:89
rtabmap::LocalGridMaker::isGridFromDepth
bool isGridFromDepth() const
Definition: LocalGridMaker.h:50
rtabmap::LocalGridMaker::isMapFrameProjection
bool isMapFrameProjection() const
Definition: LocalGridMaker.h:51
rtabmap::LocalGridMaker::parameters_
ParametersMap parameters_
Definition: LocalGridMaker.h:79
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::LocalGridMaker::scanDecimation_
int scanDecimation_
Definition: LocalGridMaker.h:88
rtabmap::LocalGridMaker::flatObstaclesDetected_
bool flatObstaclesDetected_
Definition: LocalGridMaker.h:99
rtabmap::LocalGridMaker::projMapFrame_
bool projMapFrame_
Definition: LocalGridMaker.h:92
rtabmap::Signature
Definition: Signature.h:48


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:11