GridMapPclConverter.cpp
Go to the documentation of this file.
1 /*
2  * GridMapPclConverter.cpp
3  *
4  * Created on: Oct 19, 2016
5  * Author: Dominic Jud
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
11 namespace grid_map {
12 
13 bool GridMapPclConverter::initializeFromPolygonMesh(const pcl::PolygonMesh& mesh, const double resolution, grid_map::GridMap& gridMap) {
14  pcl::PointCloud<pcl::PointXYZ> cloud;
15  pcl::fromPCLPointCloud2(mesh.cloud, cloud);
16  pcl::PointXYZ minBound;
17  pcl::PointXYZ maxBound;
18  pcl::getMinMax3D(cloud, minBound, maxBound);
19 
20  grid_map::Length length = grid_map::Length(maxBound.x - minBound.x, maxBound.y - minBound.y);
21  grid_map::Position position = grid_map::Position((maxBound.x + minBound.x) / 2.0, (maxBound.y + minBound.y) / 2.0);
22  gridMap.setGeometry(length, resolution, position);
23 
24  return true;
25 }
26 
27 bool GridMapPclConverter::addLayerFromPolygonMesh(const pcl::PolygonMesh& mesh, const std::string& layer, grid_map::GridMap& gridMap) {
28  // Adding a layer to the grid map to put data into
29  gridMap.add(layer);
30  // Converting out of binary cloud data
31  pcl::PointCloud<pcl::PointXYZ> cloud;
32  pcl::fromPCLPointCloud2(mesh.cloud, cloud);
33  // Direction and max height for projection ray
34  const Eigen::Vector3f ray = -Eigen::Vector3f::UnitZ();
35  pcl::PointXYZ minBound;
36  pcl::PointXYZ maxBound;
37  pcl::getMinMax3D(cloud, minBound, maxBound);
38 
39  // Iterating over the triangles in the mesh
40  for (const pcl::Vertices& polygon : mesh.polygons) {
41  // Testing this is a triangle
42  assert(polygon.vertices.size() == 3);
43  // Getting the vertices of the triangle (as a single matrix)
44  Eigen::Matrix3f triangleVertexMatrix;
45  triangleVertexMatrix.row(0) = cloud[polygon.vertices[0]].getVector3fMap();
46  triangleVertexMatrix.row(1) = cloud[polygon.vertices[1]].getVector3fMap();
47  triangleVertexMatrix.row(2) = cloud[polygon.vertices[2]].getVector3fMap();
48  // Getting the bounds in the XY plane (down projection)
49  float maxX = triangleVertexMatrix.col(0).maxCoeff();
50  float minX = triangleVertexMatrix.col(0).minCoeff();
51  float maxY = triangleVertexMatrix.col(1).maxCoeff();
52  float minY = triangleVertexMatrix.col(1).minCoeff();
53  // Iterating over the grid cells in the a submap below the triangle
54  grid_map::Length length(maxX - minX, maxY - minY);
55  grid_map::Position position((maxX + minX) / 2.0, (maxY + minY) / 2.0);
56  bool isSuccess;
57  SubmapGeometry submap(gridMap, position, length, isSuccess);
58  if (isSuccess) {
59  for (grid_map::SubmapIterator iterator(submap); !iterator.isPastEnd(); ++iterator) {
60  // Cell position
61  const Index index(*iterator);
62  grid_map::Position vertexPositionXY;
63  gridMap.getPosition(index, vertexPositionXY);
64  // Ray origin
65  Eigen::Vector3f point(vertexPositionXY.x(), vertexPositionXY.y(), maxBound.z + 1.0);
66  // Vertical ray/triangle intersection
67  Eigen::Vector3f intersectionPoint;
68  if (rayTriangleIntersect(point, ray, triangleVertexMatrix, intersectionPoint)) {
69  // If data already present in this cell, taking the max, else setting the data
70  if (gridMap.isValid(index, layer)) {
71  gridMap.at(layer, index) = std::max(gridMap.at(layer, index), intersectionPoint.z());
72  } else {
73  gridMap.at(layer, index) = intersectionPoint.z();
74  }
75  }
76  }
77  }
78  }
79  // Success
80  return true;
81 }
82 
83 bool GridMapPclConverter::rayTriangleIntersect(const Eigen::Vector3f& point, const Eigen::Vector3f& ray,
84  const Eigen::Matrix3f& triangleVertexMatrix, Eigen::Vector3f& intersectionPoint) {
85  // Algorithm here is adapted from:
86  // http://softsurfer.com/Archive/algorithm_0105/algorithm_0105.htm#intersect_RayTriangle()
87  //
88  // Original copyright notice:
89  // Copyright 2001, softSurfer (www.softsurfer.com)
90  // This code may be freely used and modified for any purpose
91  // providing that this copyright notice is included with it.
92 
93  const Eigen::Vector3f a = triangleVertexMatrix.row(0);
94  const Eigen::Vector3f b = triangleVertexMatrix.row(1);
95  const Eigen::Vector3f c = triangleVertexMatrix.row(2);
96  const Eigen::Vector3f u = b - a;
97  const Eigen::Vector3f v = c - a;
98  const Eigen::Vector3f n = u.cross(v);
99  const float n_dot_ray = n.dot(ray);
100 
101  if (std::fabs(n_dot_ray) < 1e-9) {
102  return false;
103  }
104 
105  const float r = n.dot(a - point) / n_dot_ray;
106 
107  if (r < 0) {
108  return false;
109  }
110 
111  // Note(alexmillane): The addition of this comparison delta (not in the
112  // original algorithm) means that rays intersecting the edge of triangles are
113  // treated at hits.
114  constexpr float delta = 1e-5;
115 
116  const Eigen::Vector3f w = point + r * ray - a;
117  const float denominator = u.dot(v) * u.dot(v) - u.dot(u) * v.dot(v);
118  const float s_numerator = u.dot(v) * w.dot(v) - v.dot(v) * w.dot(u);
119  const float s = s_numerator / denominator;
120  if (s < (0 - delta) || s > (1 + delta)) {
121  return false;
122  }
123 
124  const float t_numerator = u.dot(v) * w.dot(u) - u.dot(u) * w.dot(v);
125  const float t = t_numerator / denominator;
126  if (t < (0 - delta) || s + t > (1 + delta)) {
127  return false;
128  }
129 
130  intersectionPoint = a + s * u + t * v;
131 
132  return true;
133 }
134 
135 } /* namespace grid_map */
Eigen::Array2i Index
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
bool getPosition(const Index &index, Position &position) const
XmlRpcServer s
bool isValid(const Index &index) const
Eigen::Vector2d Position
float & at(const std::string &layer, const Index &index)
TFSIMD_FORCE_INLINE const tfScalar & w() const
void add(const std::string &layer, const double value=NAN)
static bool rayTriangleIntersect(const Eigen::Vector3f &point, const Eigen::Vector3f &ray, const Eigen::Matrix3f &triangleVertices, Eigen::Vector3f &intersectionPoint)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
static bool addLayerFromPolygonMesh(const pcl::PolygonMesh &mesh, const std::string &layer, grid_map::GridMap &gridMap)
Eigen::Array2d Length
static bool initializeFromPolygonMesh(const pcl::PolygonMesh &mesh, const double resolution, grid_map::GridMap &gridMap)


grid_map_pcl
Author(s): Dominic Jud , Edo Jelavic
autogenerated on Tue Jun 1 2021 02:13:43