LocalMapMaker.hpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, 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 CORELIB_INCLUDE_RTABMAP_CORE_IMPL_LOCALMAP_HPP_
29 #define CORELIB_INCLUDE_RTABMAP_CORE_IMPL_LOCALMAP_HPP_
30 
34 
35 namespace rtabmap {
36 
37 template<typename PointT>
38 typename pcl::PointCloud<PointT>::Ptr LocalGridMaker::segmentCloud(
39  const typename pcl::PointCloud<PointT>::Ptr & cloudIn,
40  const pcl::IndicesPtr & indicesIn,
41  const Transform & pose,
42  const cv::Point3f & viewPoint,
43  pcl::IndicesPtr & groundIndices,
44  pcl::IndicesPtr & obstaclesIndices,
45  pcl::IndicesPtr * flatObstacles) const
46 {
47  groundIndices.reset(new std::vector<int>);
48  obstaclesIndices.reset(new std::vector<int>);
49  if(flatObstacles)
50  {
51  flatObstacles->reset(new std::vector<int>);
52  }
53 
54  typename pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
55  pcl::IndicesPtr indices(new std::vector<int>);
56 
58  {
59  // voxelize to grid cell size
60  cloud = util3d::voxelize(cloudIn, indicesIn, cellSize_);
61 
62  indices->resize(cloud->size());
63  for(unsigned int i=0; i<indices->size(); ++i)
64  {
65  indices->at(i) = i;
66  }
67  }
68  else
69  {
70  cloud = cloudIn;
71  if(indicesIn->empty() && cloud->is_dense)
72  {
73  indices->resize(cloud->size());
74  for(unsigned int i=0; i<indices->size(); ++i)
75  {
76  indices->at(i) = i;
77  }
78  }
79  else
80  {
81  indices = indicesIn;
82  }
83  }
84 
85  // add pose rotation without yaw
86  float roll, pitch, yaw;
87  pose.getEulerAngles(roll, pitch, yaw);
88  UDEBUG("node.getPose()=%s projMapFrame_=%d", pose.prettyPrint().c_str(), projMapFrame_?1:0);
89  cloud = util3d::transformPointCloud(cloud, Transform(0,0, projMapFrame_?pose.z():0, roll, pitch, 0));
90 
91  // filter footprint
92  if(footprintLength_ > 0.0f || footprintWidth_ > 0.0f || footprintHeight_ > 0.0f)
93  {
95  cloud,
96  indices,
97  Eigen::Vector4f(
100  0,
101  1),
102  Eigen::Vector4f(
106  1),
108  true);
109  }
110 
111  // filter ground/obstacles zone
112  if(minGroundHeight_ != 0.0f || maxObstacleHeight_ != 0.0f)
113  {
114  indices = util3d::passThrough(cloud, indices, "z",
117  UDEBUG("indices after max obstacles height filtering = %d", (int)indices->size());
118  }
119 
120  if(indices->size())
121  {
123  {
124  UDEBUG("normalKSearch=%d", normalKSearch_);
125  UDEBUG("maxGroundAngle=%f", maxGroundAngle_);
126  UDEBUG("Cluster radius=%f", clusterRadius_);
127  UDEBUG("flatObstaclesDetected=%d", flatObstaclesDetected_?1:0);
128  UDEBUG("maxGroundHeight=%f", maxGroundHeight_);
129  UDEBUG("groundNormalsUp=%f", groundNormalsUp_);
130  util3d::segmentObstaclesFromGround<PointT>(
131  cloud,
132  indices,
133  groundIndices,
134  obstaclesIndices,
141  flatObstacles,
142  Eigen::Vector4f(viewPoint.x, viewPoint.y, viewPoint.z+(projMapFrame_?pose.z():0), 1),
144  UDEBUG("viewPoint=%f,%f,%f", viewPoint.x, viewPoint.y, viewPoint.z+(projMapFrame_?pose.z():0));
145  //UWARN("Saving ground.pcd and obstacles.pcd");
146  //pcl::io::savePCDFile("ground.pcd", *cloud, *groundIndices);
147  //pcl::io::savePCDFile("obstacles.pcd", *cloud, *obstaclesIndices);
148  }
149  else
150  {
151  UDEBUG("");
152  // passthrough filter
153  groundIndices = rtabmap::util3d::passThrough(cloud, indices, "z",
156 
157  pcl::IndicesPtr notObstacles = groundIndices;
158  if(indices->size())
159  {
160  notObstacles = util3d::extractIndices(cloud, indices, true);
161  notObstacles = util3d::concatenate(notObstacles, groundIndices);
162  }
163  obstaclesIndices = rtabmap::util3d::extractIndices(cloud, notObstacles, true);
164  }
165 
166  UDEBUG("groundIndices=%d obstaclesIndices=%d", (int)groundIndices->size(), (int)obstaclesIndices->size());
167 
168  // Do radius filtering after voxel filtering ( a lot faster)
170  {
171  UDEBUG("Radius filtering (%ld ground %ld obstacles, radius=%f k=%d)",
172  groundIndices->size(),
173  obstaclesIndices->size()+(flatObstacles?(*flatObstacles)->size():0),
176  if(groundIndices->size())
177  {
179  }
180  if(obstaclesIndices->size())
181  {
182  obstaclesIndices = rtabmap::util3d::radiusFiltering(cloud, obstaclesIndices, noiseFilteringRadius_, noiseFilteringMinNeighbors_);
183  }
184  if(flatObstacles && (*flatObstacles)->size())
185  {
187  }
188  UDEBUG("Radius filtering end (%ld ground %ld obstacles)",
189  groundIndices->size(),
190  obstaclesIndices->size()+(flatObstacles?(*flatObstacles)->size():0));
191 
192  if(groundIndices->empty() && obstaclesIndices->empty())
193  {
194  UWARN("Cloud (with %d points) is empty after noise "
195  "filtering. Occupancy grid cannot be "
196  "created.",
197  (int)cloud->size());
198 
199  }
200  }
201  }
202  return cloud;
203 }
204 
205 }
206 
207 
208 #endif /* CORELIB_INCLUDE_RTABMAP_CORE_IMPL_LOCALMAP_HPP_ */
glm::min
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
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::util3d::cropBox
pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(const pcl::PCLPointCloud2::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
Definition: util3d_filtering.cpp:826
glm::yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
rtabmap::util3d::passThrough
pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
Definition: util3d_filtering.cpp:730
rtabmap::util3d::voxelize
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
Definition: util3d_filtering.cpp:613
rtabmap::LocalGridMaker::normalKSearch_
int normalKSearch_
Definition: LocalGridMaker.h:94
rtabmap::LocalGridMaker::footprintHeight_
float footprintHeight_
Definition: LocalGridMaker.h:87
rtabmap::util3d::concatenate
pcl::IndicesPtr RTABMAP_CORE_EXPORT concatenate(const std::vector< pcl::IndicesPtr > &indices)
Concatenate a vector of indices to a single vector.
Definition: util3d.cpp:3352
indices
indices
rtabmap::Transform::z
float & z()
Definition: Transform.h:94
rtabmap::util3d::transformPointCloud
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
Definition: util3d_transforms.cpp:107
rtabmap::Transform::getEulerAngles
void getEulerAngles(float &roll, float &pitch, float &yaw) const
Definition: Transform.cpp:263
rtabmap::Transform::prettyPrint
std::string prettyPrint() const
Definition: Transform.cpp:326
util3d_transforms.h
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
glm::max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
rtabmap::LocalGridMaker::footprintWidth_
float footprintWidth_
Definition: LocalGridMaker.h:86
rtabmap::util3d::extractIndices
pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
Definition: util3d_filtering.cpp:2299
util3d_mapping.h
glm::pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
rtabmap::LocalGridMaker::maxGroundAngle_
float maxGroundAngle_
Definition: LocalGridMaker.h:96
UWARN
#define UWARN(...)
f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
ULogger.h
ULogger class and convenient macros.
rtabmap::LocalGridMaker::minGroundHeight_
float minGroundHeight_
Definition: LocalGridMaker.h:100
rtabmap::Transform
Definition: Transform.h:41
rtabmap::LocalGridMaker::segmentCloud
pcl::PointCloud< PointT >::Ptr segmentCloud(const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &pose, const cv::Point3f &viewPoint, pcl::IndicesPtr &groundIndices, pcl::IndicesPtr &obstaclesIndices, pcl::IndicesPtr *flatObstacles=0) const
Definition: LocalMapMaker.hpp:38
rtabmap::LocalGridMaker::groundNormalsUp_
float groundNormalsUp_
Definition: LocalGridMaker.h:95
rtabmap::LocalGridMaker::clusterRadius_
float clusterRadius_
Definition: LocalGridMaker.h:97
rtabmap::LocalGridMaker::footprintLength_
float footprintLength_
Definition: LocalGridMaker.h:85
UDEBUG
#define UDEBUG(...)
rtabmap::LocalGridMaker::preVoxelFiltering_
bool preVoxelFiltering_
Definition: LocalGridMaker.h:90
rtabmap::LocalGridMaker::cellSize_
float cellSize_
Definition: LocalGridMaker.h:89
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::LocalGridMaker::flatObstaclesDetected_
bool flatObstaclesDetected_
Definition: LocalGridMaker.h:99
i
int i
rtabmap::LocalGridMaker::projMapFrame_
bool projMapFrame_
Definition: LocalGridMaker.h:92
glm::roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
rtabmap::util3d::radiusFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
Definition: util3d_filtering.cpp:1087


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