src/shape/geometric_shapes.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2015, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
40 
41 namespace coal {
42 
43 void ConvexBase::initialize(std::shared_ptr<std::vector<Vec3s>> points_,
44  unsigned int num_points_) {
45  this->points = points_;
46  this->num_points = num_points_;
47  COAL_ASSERT(this->points->size() == this->num_points,
48  "The number of points is not consistent with the size of the "
49  "points vector",
50  std::logic_error);
51  this->num_normals_and_offsets = 0;
52  this->normals.reset();
53  this->offsets.reset();
54  this->computeCenter();
55 }
56 
57 void ConvexBase::set(std::shared_ptr<std::vector<Vec3s>> points_,
58  unsigned int num_points_) {
59  initialize(points_, num_points_);
60 }
61 
63  : ShapeBase(other),
64  num_points(other.num_points),
65  num_normals_and_offsets(other.num_normals_and_offsets),
66  center(other.center) {
67  if (other.points.get() && other.points->size() > 0) {
68  // Deep copy of other points
69  points.reset(new std::vector<Vec3s>(*other.points));
70  } else
71  points.reset();
72 
73  if (other.nneighbors_.get() && other.nneighbors_->size() > 0) {
74  // Deep copy the list of all the neighbors of all the points
75  nneighbors_.reset(new std::vector<unsigned int>(*(other.nneighbors_)));
76  if (other.neighbors.get() && other.neighbors->size() > 0) {
77  // Fill each neighbors for each point in the Convex object.
78  neighbors.reset(new std::vector<Neighbors>(other.neighbors->size()));
79  assert(neighbors->size() == points->size());
80  unsigned int* p_nneighbors = nneighbors_->data();
81 
82  std::vector<Neighbors>& neighbors_ = *neighbors;
83  const std::vector<Neighbors>& other_neighbors_ = *(other.neighbors);
84  for (size_t i = 0; i < neighbors->size(); ++i) {
85  Neighbors& n = neighbors_[i];
86  n.count_ = other_neighbors_[i].count_;
87  n.n_ = p_nneighbors;
88  p_nneighbors += n.count_;
89  }
90  } else
91  neighbors.reset();
92  } else
93  nneighbors_.reset();
94 
95  if (other.normals.get() && other.normals->size() > 0) {
96  normals.reset(new std::vector<Vec3s>(*(other.normals)));
97  } else
98  normals.reset();
99 
100  if (other.offsets.get() && other.offsets->size() > 0) {
101  offsets.reset(new std::vector<double>(*(other.offsets)));
102  } else
103  offsets.reset();
104 
106 
107  ShapeBase::operator=(*this);
108 }
109 
111 
113  center.setZero();
114  const std::vector<Vec3s>& points_ = *points;
115  for (std::size_t i = 0; i < num_points; ++i)
116  center += points_[i]; // TODO(jcarpent): vectorization
117  center /= num_points;
118 }
119 
121  CoalScalar l = n.norm();
122  if (l > 0) {
123  CoalScalar inv_l = 1.0 / l;
124  n *= inv_l;
125  d *= inv_l;
126  } else {
127  n << 1, 0, 0;
128  d = 0;
129  }
130 }
131 
133  CoalScalar l = n.norm();
134  if (l > 0) {
135  CoalScalar inv_l = 1.0 / l;
136  n *= inv_l;
137  d *= inv_l;
138  } else {
139  n << 1, 0, 0;
140  d = 0;
141  }
142 }
143 
145  computeBV<AABB>(*this, Transform3s(), aabb_local);
146  const CoalScalar ssr = this->getSweptSphereRadius();
147  if (ssr > 0) {
148  aabb_local.min_ -= Vec3s::Constant(ssr);
149  aabb_local.max_ += Vec3s::Constant(ssr);
150  }
152  aabb_radius = (aabb_local.min_ - aabb_center).norm();
153 }
154 
156  computeBV<AABB>(*this, Transform3s(), aabb_local);
157  const CoalScalar ssr = this->getSweptSphereRadius();
158  if (ssr > 0) {
159  aabb_local.min_ -= Vec3s::Constant(ssr);
160  aabb_local.max_ += Vec3s::Constant(ssr);
161  }
164 }
165 
167  computeBV<AABB>(*this, Transform3s(), aabb_local);
168  const CoalScalar ssr = this->getSweptSphereRadius();
169  if (ssr > 0) {
170  aabb_local.min_ -= Vec3s::Constant(ssr);
171  aabb_local.max_ += Vec3s::Constant(ssr);
172  }
174  aabb_radius = (aabb_local.min_ - aabb_center).norm();
175 }
176 
178  computeBV<AABB>(*this, Transform3s(), aabb_local);
179  const CoalScalar ssr = this->getSweptSphereRadius();
180  if (ssr > 0) {
181  aabb_local.min_ -= Vec3s::Constant(ssr);
182  aabb_local.max_ += Vec3s::Constant(ssr);
183  }
185  aabb_radius = (aabb_local.min_ - aabb_center).norm();
186 }
187 
189  computeBV<AABB>(*this, Transform3s(), aabb_local);
190  const CoalScalar ssr = this->getSweptSphereRadius();
191  if (ssr > 0) {
192  aabb_local.min_ -= Vec3s::Constant(ssr);
193  aabb_local.max_ += Vec3s::Constant(ssr);
194  }
196  aabb_radius = (aabb_local.min_ - aabb_center).norm();
197 }
198 
200  computeBV<AABB>(*this, Transform3s(), aabb_local);
201  const CoalScalar ssr = this->getSweptSphereRadius();
202  if (ssr > 0) {
203  aabb_local.min_ -= Vec3s::Constant(ssr);
204  aabb_local.max_ += Vec3s::Constant(ssr);
205  }
207  aabb_radius = (aabb_local.min_ - aabb_center).norm();
208 }
209 
211  computeBV<AABB>(*this, Transform3s(), aabb_local);
212  const CoalScalar ssr = this->getSweptSphereRadius();
213  if (ssr > 0) {
214  aabb_local.min_ -= Vec3s::Constant(ssr);
215  aabb_local.max_ += Vec3s::Constant(ssr);
216  }
218  aabb_radius = (aabb_local.min_ - aabb_center).norm();
219 }
220 
222  computeBV<AABB>(*this, Transform3s(), aabb_local);
223  const CoalScalar ssr = this->getSweptSphereRadius();
224  if (ssr > 0) {
225  aabb_local.min_ -= Vec3s::Constant(ssr);
226  aabb_local.max_ += Vec3s::Constant(ssr);
227  }
229  aabb_radius = (aabb_local.min_ - aabb_center).norm();
230 }
231 
233  computeBV<AABB>(*this, Transform3s(), aabb_local);
234  const CoalScalar ssr = this->getSweptSphereRadius();
235  if (ssr > 0) {
236  aabb_local.min_ -= Vec3s::Constant(ssr);
237  aabb_local.max_ += Vec3s::Constant(ssr);
238  }
240  aabb_radius = (aabb_local.min_ - aabb_center).norm();
241 }
242 
244  computeBV<AABB>(*this, Transform3s(), aabb_local);
245  const CoalScalar ssr = this->getSweptSphereRadius();
246  if (ssr > 0) {
247  aabb_local.min_ -= Vec3s::Constant(ssr);
248  aabb_local.max_ += Vec3s::Constant(ssr);
249  }
251  aabb_radius = (aabb_local.min_ - aabb_center).norm();
252 }
253 
254 } // namespace coal
coal::ConvexBase::Neighbors::n_
unsigned int * n_
Definition: coal/shape/geometric_shapes.h:689
coal::Halfspace::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:221
coal::ConvexBase::num_points
unsigned int num_points
Definition: coal/shape/geometric_shapes.h:720
coal::ConvexBase::neighbors
std::shared_ptr< std::vector< Neighbors > > neighbors
Neighbors of each vertex. It is an array of size num_points. For each vertex, it contains the number ...
Definition: coal/shape/geometric_shapes.h:732
COAL_ASSERT
#define COAL_ASSERT(check, message, exception)
Definition: include/coal/fwd.hh:82
coal::ConvexBase::~ConvexBase
virtual ~ConvexBase()
Definition: src/shape/geometric_shapes.cpp:110
coal::Ellipsoid::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:166
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::Sphere::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:155
coal::ConvexBase::ConvexBase
ConvexBase()
Construct an uninitialized convex object Initialization is done with ConvexBase::initialize.
Definition: coal/shape/geometric_shapes.h:762
coal::Cone::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:188
coal::Plane::unitNormalTest
void unitNormalTest()
Turn non-unit normal into unit.
Definition: src/shape/geometric_shapes.cpp:132
coal::Capsule::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:177
coal::Cylinder::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:199
coal::ConvexBase::normals
std::shared_ptr< std::vector< Vec3s > > normals
An array of the normals of the polygon.
Definition: coal/shape/geometric_shapes.h:723
coal::ConvexBase::Neighbors::count_
unsigned char count_
Definition: coal/shape/geometric_shapes.h:688
coal::Transform3s
Simple transform class used locally by InterpMotion.
Definition: coal/math/transform.h:55
coal::AABB::max_
Vec3s max_
The max point in the AABB.
Definition: coal/BV/AABB.h:60
coal::ConvexBase::Neighbors
Definition: coal/shape/geometric_shapes.h:687
coal::ConvexBase::num_normals_and_offsets
unsigned int num_normals_and_offsets
Definition: coal/shape/geometric_shapes.h:727
coal::ConvexBase::computeCenter
void computeCenter()
Definition: src/shape/geometric_shapes.cpp:112
coal::ShapeBase
Base class for all basic geometric shapes.
Definition: coal/shape/geometric_shapes.h:58
coal::CollisionGeometry::aabb_local
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
Definition: coal/collision_object.h:158
coal::ConvexBase::initialize
void initialize(std::shared_ptr< std::vector< Vec3s >> points_, unsigned int num_points_)
Initialize the points of the convex shape This also initializes the ConvexBase::center.
Definition: src/shape/geometric_shapes.cpp:43
coal::CollisionGeometry::aabb_radius
CoalScalar aabb_radius
AABB radius.
Definition: coal/collision_object.h:154
coal::ShapeBase::operator=
ShapeBase & operator=(const ShapeBase &other)=default
coal::AABB::center
Vec3s center() const
Center of the AABB.
Definition: coal/BV/AABB.h:164
coal::TriangleP::computeLocalAABB
void computeLocalAABB()
virtual function of compute AABB in local coordinate
Definition: src/shape/geometric_shapes.cpp:243
coal::ConvexBase::center
Vec3s center
center of the convex polytope, this is used for collision: center is guaranteed in the internal of th...
Definition: coal/shape/geometric_shapes.h:736
coal::AABB::min_
Vec3s min_
The min point in the AABB.
Definition: coal/BV/AABB.h:58
coal::ShapeBase::getSweptSphereRadius
CoalScalar getSweptSphereRadius() const
Get radius of sphere swept around the shape. This radius is always >= 0.
Definition: coal/shape/geometric_shapes.h:86
coal::Plane::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:232
coal::Halfspace::n
Vec3s n
Plane normal.
Definition: coal/shape/geometric_shapes.h:956
coal::Sphere::radius
CoalScalar radius
Radius of the sphere.
Definition: coal/shape/geometric_shapes.h:250
coal::ConvexBase::offsets
std::shared_ptr< std::vector< double > > offsets
An array of the offsets to the normals of the polygon. Note: there are as many offsets as normals.
Definition: coal/shape/geometric_shapes.h:726
coal::Halfspace::d
CoalScalar d
Plane offset.
Definition: coal/shape/geometric_shapes.h:959
coal::Plane::n
Vec3s n
Plane normal.
Definition: coal/shape/geometric_shapes.h:1034
geometric_shapes_utility.h
geometric_shapes.h
coal::Halfspace::unitNormalTest
void unitNormalTest()
Turn non-unit normal into unit.
Definition: src/shape/geometric_shapes.cpp:120
coal::CollisionGeometry::aabb_center
Vec3s aabb_center
AABB center in local coordinate.
Definition: coal/collision_object.h:151
coal::ConvexBase::nneighbors_
std::shared_ptr< std::vector< unsigned int > > nneighbors_
Array of indices of the neighbors of each vertex. Since we don't know a priori the number of neighbor...
Definition: coal/shape/geometric_shapes.h:801
coal::ConvexBase::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:210
coal::ConvexBase::support_warm_starts
SupportWarmStartPolytope support_warm_starts
Support warm start polytopes.
Definition: coal/shape/geometric_shapes.h:757
coal::ConvexBase::points
std::shared_ptr< std::vector< Vec3s > > points
An array of the points of the polygon.
Definition: coal/shape/geometric_shapes.h:719
coal::Box::computeLocalAABB
void computeLocalAABB()
Compute AABB.
Definition: src/shape/geometric_shapes.cpp:144
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::Plane::d
CoalScalar d
Plane offset.
Definition: coal/shape/geometric_shapes.h:1037
coal::ConvexBase::set
void set(std::shared_ptr< std::vector< Vec3s >> points_, unsigned int num_points_)
Set the points of the convex shape.
Definition: src/shape/geometric_shapes.cpp:57
coal::ConvexBase
Base for convex polytope.
Definition: coal/shape/geometric_shapes.h:645


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