src/octree.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020-2023, INRIA
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Open Source Robotics Foundation nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include "coal/octree.h"
36 
37 #include <array>
38 
39 namespace coal {
40 namespace internal {
41 struct Neighbors {
42  char value;
43  Neighbors() : value(0) {}
44  bool minusX() const { return value & 0x1; }
45  bool plusX() const { return value & 0x2; }
46  bool minusY() const { return value & 0x4; }
47  bool plusY() const { return value & 0x8; }
48  bool minusZ() const { return value & 0x10; }
49  bool plusZ() const { return value & 0x20; }
50  void hasNeighboordMinusX() { value |= 0x1; }
51  void hasNeighboordPlusX() { value |= 0x2; }
52  void hasNeighboordMinusY() { value |= 0x4; }
53  void hasNeighboordPlusY() { value |= 0x8; }
54  void hasNeighboordMinusZ() { value |= 0x10; }
55  void hasNeighboordPlusZ() { value |= 0x20; }
56 }; // struct neighbors
57 
58 void computeNeighbors(const std::vector<Vec6s>& boxes,
59  std::vector<Neighbors>& neighbors) {
60  typedef std::vector<Vec6s> VectorVec6s;
61  CoalScalar fixedSize = -1;
62  CoalScalar e(1e-8);
63  for (std::size_t i = 0; i < boxes.size(); ++i) {
64  const Vec6s& box(boxes[i]);
65  Neighbors& n(neighbors[i]);
66  CoalScalar x(box[0]);
67  CoalScalar y(box[1]);
68  CoalScalar z(box[2]);
69  CoalScalar s(box[3]);
70  if (fixedSize == -1)
71  fixedSize = s;
72  else
73  assert(s == fixedSize);
74 
75  for (VectorVec6s::const_iterator it = boxes.begin(); it != boxes.end();
76  ++it) {
77  const Vec6s& otherBox = *it;
78  CoalScalar xo(otherBox[0]);
79  CoalScalar yo(otherBox[1]);
80  CoalScalar zo(otherBox[2]);
81  // if (fabs(x-xo) < e && fabs(y-yo) < e && fabs(z-zo) < e){
82  // continue;
83  // }
84  if ((fabs(x - xo - s) < e) && (fabs(y - yo) < e) && (fabs(z - zo) < e)) {
86  } else if ((fabs(x - xo + s) < e) && (fabs(y - yo) < e) &&
87  (fabs(z - zo) < e)) {
89  } else if ((fabs(x - xo) < e) && (fabs(y - yo - s) < e) &&
90  (fabs(z - zo) < e)) {
92  } else if ((fabs(x - xo) < e) && (fabs(y - yo + s) < e) &&
93  (fabs(z - zo) < e)) {
95  } else if ((fabs(x - xo) < e) && (fabs(y - yo) < e) &&
96  (fabs(z - zo - s) < e)) {
98  } else if ((fabs(x - xo) < e) && (fabs(y - yo) < e) &&
99  (fabs(z - zo + s) < e)) {
100  n.hasNeighboordPlusZ();
101  }
102  }
103  }
104 }
105 
106 } // namespace internal
107 
108 void OcTree::exportAsObjFile(const std::string& filename) const {
109  std::vector<Vec6s> boxes(this->toBoxes());
110  std::vector<internal::Neighbors> neighbors(boxes.size());
111  internal::computeNeighbors(boxes, neighbors);
112  // compute list of vertices and faces
113 
114  typedef std::vector<Vec3s> VectorVec3s;
115  std::vector<Vec3s> vertices;
116 
117  typedef std::array<std::size_t, 4> Array4;
118  typedef std::vector<Array4> VectorArray4;
119  std::vector<Array4> faces;
120 
121  for (std::size_t i = 0; i < boxes.size(); ++i) {
122  const Vec6s& box(boxes[i]);
123  internal::Neighbors& n(neighbors[i]);
124 
125  CoalScalar x(box[0]);
126  CoalScalar y(box[1]);
127  CoalScalar z(box[2]);
128  CoalScalar size(box[3]);
129 
130  vertices.push_back(Vec3s(x - .5 * size, y - .5 * size, z - .5 * size));
131  vertices.push_back(Vec3s(x + .5 * size, y - .5 * size, z - .5 * size));
132  vertices.push_back(Vec3s(x - .5 * size, y + .5 * size, z - .5 * size));
133  vertices.push_back(Vec3s(x + .5 * size, y + .5 * size, z - .5 * size));
134  vertices.push_back(Vec3s(x - .5 * size, y - .5 * size, z + .5 * size));
135  vertices.push_back(Vec3s(x + .5 * size, y - .5 * size, z + .5 * size));
136  vertices.push_back(Vec3s(x - .5 * size, y + .5 * size, z + .5 * size));
137  vertices.push_back(Vec3s(x + .5 * size, y + .5 * size, z + .5 * size));
138 
139  // Add face only if box has no neighbor with the same face
140  if (!n.minusX()) {
141  Array4 a = {{8 * i + 1, 8 * i + 5, 8 * i + 7, 8 * i + 3}};
142  faces.push_back(a);
143  }
144  if (!n.plusX()) {
145  Array4 a = {{8 * i + 2, 8 * i + 4, 8 * i + 8, 8 * i + 6}};
146  faces.push_back(a);
147  }
148  if (!n.minusY()) {
149  Array4 a = {{8 * i + 1, 8 * i + 2, 8 * i + 6, 8 * i + 5}};
150  faces.push_back(a);
151  }
152  if (!n.plusY()) {
153  Array4 a = {{8 * i + 4, 8 * i + 3, 8 * i + 7, 8 * i + 8}};
154  faces.push_back(a);
155  }
156  if (!n.minusZ()) {
157  Array4 a = {{8 * i + 1, 8 * i + 2, 8 * i + 4, 8 * i + 3}};
158  faces.push_back(a);
159  }
160  if (!n.plusZ()) {
161  Array4 a = {{8 * i + 5, 8 * i + 6, 8 * i + 8, 8 * i + 7}};
162  faces.push_back(a);
163  }
164  }
165  // write obj in a file
166  std::ofstream os;
167  os.open(filename);
168  if (!os.is_open())
170  (std::string("failed to open file \"") + filename + std::string("\""))
171  .c_str(),
172  std::runtime_error);
173  // write vertices
174  os << "# list of vertices\n";
175  for (VectorVec3s::const_iterator it = vertices.begin(); it != vertices.end();
176  ++it) {
177  const Vec3s& v = *it;
178  os << "v " << v[0] << " " << v[1] << " " << v[2] << '\n';
179  }
180  os << "\n# list of faces\n";
181  for (VectorArray4::const_iterator it = faces.begin(); it != faces.end();
182  ++it) {
183  const Array4& f = *it;
184  os << "f " << f[0] << " " << f[1] << " " << f[2] << " " << f[3] << '\n';
185  }
186 }
187 
189  const Eigen::Matrix<CoalScalar, Eigen::Dynamic, 3>& point_cloud,
190  const CoalScalar resolution) {
191  typedef Eigen::Matrix<CoalScalar, Eigen::Dynamic, 3> InputType;
192  typedef InputType::ConstRowXpr RowType;
193 
194  shared_ptr<octomap::OcTree> octree(new octomap::OcTree(resolution));
195  for (Eigen::DenseIndex row_id = 0; row_id < point_cloud.rows(); ++row_id) {
196  RowType row = point_cloud.row(row_id);
197  octree->updateNode(row[0], row[1], row[2], true, true);
198  }
199  octree->updateInnerOccupancy();
200 
201  return OcTreePtr_t(new OcTree(octree));
202 }
203 } // namespace coal
coal::internal::Neighbors::minusY
bool minusY() const
Definition: src/octree.cpp:46
octree.h
coal::OcTree::toBoxes
std::vector< Vec6s > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes....
Definition: coal/octree.h:178
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::internal::Neighbors::value
char value
Definition: src/octree.cpp:42
collision_manager.box
box
Definition: collision_manager.py:11
y
y
coal::internal::Neighbors::hasNeighboordMinusX
void hasNeighboordMinusX()
Definition: src/octree.cpp:50
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::internal::Neighbors::hasNeighboordPlusZ
void hasNeighboordPlusZ()
Definition: src/octree.cpp:55
coal::OcTree::size
unsigned long size() const
Returns the size of the octree.
Definition: coal/octree.h:150
coal::internal::Neighbors::Neighbors
Neighbors()
Definition: src/octree.cpp:43
coal::internal::Neighbors::minusZ
bool minusZ() const
Definition: src/octree.cpp:48
octree
Definition: octree.py:1
coal::makeOctree
COAL_DLLAPI OcTreePtr_t makeOctree(const Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3 > &point_cloud, const CoalScalar resolution)
Build an OcTree from a point cloud and a given resolution.
Definition: src/octree.cpp:188
coal::internal::Neighbors::plusZ
bool plusZ() const
Definition: src/octree.cpp:49
coal::internal::Neighbors::hasNeighboordPlusX
void hasNeighboordPlusX()
Definition: src/octree.cpp:51
a
list a
coal::internal::Neighbors
Definition: src/octree.cpp:41
coal::internal::Neighbors::plusX
bool plusX() const
Definition: src/octree.cpp:45
collision-bench.filename
filename
Definition: collision-bench.py:6
COAL_THROW_PRETTY
#define COAL_THROW_PRETTY(message, exception)
Definition: include/coal/fwd.hh:64
coal::Vec6s
Eigen::Matrix< CoalScalar, 6, 1 > Vec6s
Definition: coal/data_types.h:79
x
x
coal::internal::computeNeighbors
void computeNeighbors(const std::vector< Vec6s > &boxes, std::vector< Neighbors > &neighbors)
Definition: src/octree.cpp:58
coal::OcTreePtr_t
shared_ptr< OcTree > OcTreePtr_t
Definition: include/coal/fwd.hh:144
coal::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: coal/octree.h:53
coal::internal::Neighbors::plusY
bool plusY() const
Definition: src/octree.cpp:47
coal::internal::Neighbors::hasNeighboordMinusZ
void hasNeighboordMinusZ()
Definition: src/octree.cpp:54
coal::internal::Neighbors::hasNeighboordPlusY
void hasNeighboordPlusY()
Definition: src/octree.cpp:53
coal::OcTree::exportAsObjFile
void exportAsObjFile(const std::string &filename) const
Definition: src/octree.cpp:108
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::internal::Neighbors::hasNeighboordMinusY
void hasNeighboordMinusY()
Definition: src/octree.cpp:52
obb.v
list v
Definition: obb.py:48
coal::internal::Neighbors::minusX
bool minusX() const
Definition: src/octree.cpp:44


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58