geometric_shapes_utility.h
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 
38 #ifndef HPP_FCL_GEOMETRIC_SHAPES_UTILITY_H
39 #define HPP_FCL_GEOMETRIC_SHAPES_UTILITY_H
40 
41 #include <vector>
43 #include <hpp/fcl/BV/BV.h>
45 
46 namespace hpp {
47 namespace fcl {
48 
50 namespace details {
53 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Box& box,
54  const Transform3f& tf);
55 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Sphere& sphere,
56  const Transform3f& tf);
57 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Ellipsoid& ellipsoid,
58  const Transform3f& tf);
59 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Capsule& capsule,
60  const Transform3f& tf);
61 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Cone& cone,
62  const Transform3f& tf);
63 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const Cylinder& cylinder,
64  const Transform3f& tf);
65 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const ConvexBase& convex,
66  const Transform3f& tf);
67 HPP_FCL_DLLAPI std::vector<Vec3f> getBoundVertices(const TriangleP& triangle,
68  const Transform3f& tf);
69 } // namespace details
71 
73 template <typename BV, typename S>
74 inline void computeBV(const S& s, const Transform3f& tf, BV& bv) {
75  std::vector<Vec3f> convex_bound_vertices = details::getBoundVertices(s, tf);
76  fit(&convex_bound_vertices[0], (unsigned int)convex_bound_vertices.size(),
77  bv);
78 }
79 
80 template <>
81 HPP_FCL_DLLAPI void computeBV<AABB, Box>(const Box& s, const Transform3f& tf,
82  AABB& bv);
83 
84 template <>
85 HPP_FCL_DLLAPI void computeBV<AABB, Sphere>(const Sphere& s,
86  const Transform3f& tf, AABB& bv);
87 
88 template <>
89 HPP_FCL_DLLAPI void computeBV<AABB, Ellipsoid>(const Ellipsoid& e,
90  const Transform3f& tf, AABB& bv);
91 
92 template <>
93 HPP_FCL_DLLAPI void computeBV<AABB, Capsule>(const Capsule& s,
94  const Transform3f& tf, AABB& bv);
95 
96 template <>
97 HPP_FCL_DLLAPI void computeBV<AABB, Cone>(const Cone& s, const Transform3f& tf,
98  AABB& bv);
99 
100 template <>
101 HPP_FCL_DLLAPI void computeBV<AABB, Cylinder>(const Cylinder& s,
102  const Transform3f& tf, AABB& bv);
103 
104 template <>
105 HPP_FCL_DLLAPI void computeBV<AABB, ConvexBase>(const ConvexBase& s,
106  const Transform3f& tf,
107  AABB& bv);
108 
109 template <>
110 HPP_FCL_DLLAPI void computeBV<AABB, TriangleP>(const TriangleP& s,
111  const Transform3f& tf, AABB& bv);
112 
113 template <>
114 HPP_FCL_DLLAPI void computeBV<AABB, Halfspace>(const Halfspace& s,
115  const Transform3f& tf, AABB& bv);
116 
117 template <>
118 HPP_FCL_DLLAPI void computeBV<AABB, Plane>(const Plane& s,
119  const Transform3f& tf, AABB& bv);
120 
121 template <>
122 HPP_FCL_DLLAPI void computeBV<OBB, Box>(const Box& s, const Transform3f& tf,
123  OBB& bv);
124 
125 template <>
126 HPP_FCL_DLLAPI void computeBV<OBB, Sphere>(const Sphere& s,
127  const Transform3f& tf, OBB& bv);
128 
129 template <>
130 HPP_FCL_DLLAPI void computeBV<OBB, Capsule>(const Capsule& s,
131  const Transform3f& tf, OBB& bv);
132 
133 template <>
134 HPP_FCL_DLLAPI void computeBV<OBB, Cone>(const Cone& s, const Transform3f& tf,
135  OBB& bv);
136 
137 template <>
138 HPP_FCL_DLLAPI void computeBV<OBB, Cylinder>(const Cylinder& s,
139  const Transform3f& tf, OBB& bv);
140 
141 template <>
142 HPP_FCL_DLLAPI void computeBV<OBB, ConvexBase>(const ConvexBase& s,
143  const Transform3f& tf, OBB& bv);
144 
145 template <>
146 HPP_FCL_DLLAPI void computeBV<OBB, Halfspace>(const Halfspace& s,
147  const Transform3f& tf, OBB& bv);
148 
149 template <>
150 HPP_FCL_DLLAPI void computeBV<RSS, Halfspace>(const Halfspace& s,
151  const Transform3f& tf, RSS& bv);
152 
153 template <>
154 HPP_FCL_DLLAPI void computeBV<OBBRSS, Halfspace>(const Halfspace& s,
155  const Transform3f& tf,
156  OBBRSS& bv);
157 
158 template <>
159 HPP_FCL_DLLAPI void computeBV<kIOS, Halfspace>(const Halfspace& s,
160  const Transform3f& tf, kIOS& bv);
161 
162 template <>
163 HPP_FCL_DLLAPI void computeBV<KDOP<16>, Halfspace>(const Halfspace& s,
164  const Transform3f& tf,
165  KDOP<16>& bv);
166 
167 template <>
168 HPP_FCL_DLLAPI void computeBV<KDOP<18>, Halfspace>(const Halfspace& s,
169  const Transform3f& tf,
170  KDOP<18>& bv);
171 
172 template <>
173 HPP_FCL_DLLAPI void computeBV<KDOP<24>, Halfspace>(const Halfspace& s,
174  const Transform3f& tf,
175  KDOP<24>& bv);
176 
177 template <>
178 HPP_FCL_DLLAPI void computeBV<OBB, Plane>(const Plane& s, const Transform3f& tf,
179  OBB& bv);
180 
181 template <>
182 HPP_FCL_DLLAPI void computeBV<RSS, Plane>(const Plane& s, const Transform3f& tf,
183  RSS& bv);
184 
185 template <>
186 HPP_FCL_DLLAPI void computeBV<OBBRSS, Plane>(const Plane& s,
187  const Transform3f& tf, OBBRSS& bv);
188 
189 template <>
190 HPP_FCL_DLLAPI void computeBV<kIOS, Plane>(const Plane& s,
191  const Transform3f& tf, kIOS& bv);
192 
193 template <>
194 HPP_FCL_DLLAPI void computeBV<KDOP<16>, Plane>(const Plane& s,
195  const Transform3f& tf,
196  KDOP<16>& bv);
197 
198 template <>
199 HPP_FCL_DLLAPI void computeBV<KDOP<18>, Plane>(const Plane& s,
200  const Transform3f& tf,
201  KDOP<18>& bv);
202 
203 template <>
204 HPP_FCL_DLLAPI void computeBV<KDOP<24>, Plane>(const Plane& s,
205  const Transform3f& tf,
206  KDOP<24>& bv);
207 
210 HPP_FCL_DLLAPI void constructBox(const AABB& bv, Box& box, Transform3f& tf);
211 
212 HPP_FCL_DLLAPI void constructBox(const OBB& bv, Box& box, Transform3f& tf);
213 
214 HPP_FCL_DLLAPI void constructBox(const OBBRSS& bv, Box& box, Transform3f& tf);
215 
216 HPP_FCL_DLLAPI void constructBox(const kIOS& bv, Box& box, Transform3f& tf);
217 
218 HPP_FCL_DLLAPI void constructBox(const RSS& bv, Box& box, Transform3f& tf);
219 
220 HPP_FCL_DLLAPI void constructBox(const KDOP<16>& bv, Box& box, Transform3f& tf);
221 
222 HPP_FCL_DLLAPI void constructBox(const KDOP<18>& bv, Box& box, Transform3f& tf);
223 
224 HPP_FCL_DLLAPI void constructBox(const KDOP<24>& bv, Box& box, Transform3f& tf);
225 
226 HPP_FCL_DLLAPI void constructBox(const AABB& bv, const Transform3f& tf_bv,
227  Box& box, Transform3f& tf);
228 
229 HPP_FCL_DLLAPI void constructBox(const OBB& bv, const Transform3f& tf_bv,
230  Box& box, Transform3f& tf);
231 
232 HPP_FCL_DLLAPI void constructBox(const OBBRSS& bv, const Transform3f& tf_bv,
233  Box& box, Transform3f& tf);
234 
235 HPP_FCL_DLLAPI void constructBox(const kIOS& bv, const Transform3f& tf_bv,
236  Box& box, Transform3f& tf);
237 
238 HPP_FCL_DLLAPI void constructBox(const RSS& bv, const Transform3f& tf_bv,
239  Box& box, Transform3f& tf);
240 
241 HPP_FCL_DLLAPI void constructBox(const KDOP<16>& bv, const Transform3f& tf_bv,
242  Box& box, Transform3f& tf);
243 
244 HPP_FCL_DLLAPI void constructBox(const KDOP<18>& bv, const Transform3f& tf_bv,
245  Box& box, Transform3f& tf);
246 
247 HPP_FCL_DLLAPI void constructBox(const KDOP<24>& bv, const Transform3f& tf_bv,
248  Box& box, Transform3f& tf);
249 
250 HPP_FCL_DLLAPI Halfspace transform(const Halfspace& a, const Transform3f& tf);
251 
252 HPP_FCL_DLLAPI Plane transform(const Plane& a, const Transform3f& tf);
253 
254 } // namespace fcl
255 
256 } // namespace hpp
257 
258 #endif
hpp::fcl::computeBV< AABB, TriangleP >
HPP_FCL_DLLAPI void computeBV< AABB, TriangleP >(const TriangleP &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:366
hpp::fcl::transform
HPP_FCL_DLLAPI Halfspace transform(const Halfspace &a, const Transform3f &tf)
Definition: geometric_shapes_utility.cpp:248
hpp::fcl::computeBV< AABB, Box >
HPP_FCL_DLLAPI void computeBV< AABB, Box >(const Box &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:275
collision_manager.box
box
Definition: collision_manager.py:11
hpp::fcl::computeBV< OBB, Sphere >
HPP_FCL_DLLAPI void computeBV< OBB, Sphere >(const Sphere &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:450
hpp::fcl::computeBV< AABB, Sphere >
HPP_FCL_DLLAPI void computeBV< AABB, Sphere >(const Sphere &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:285
collision_manager.sphere
sphere
Definition: collision_manager.py:4
hpp::fcl::computeBV< OBB, Halfspace >
HPP_FCL_DLLAPI void computeBV< OBB, Halfspace >(const Halfspace &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:503
hpp::fcl::computeBV< OBBRSS, Halfspace >
HPP_FCL_DLLAPI void computeBV< OBBRSS, Halfspace >(const Halfspace &s, const Transform3f &tf, OBBRSS &bv)
Definition: geometric_shapes_utility.cpp:520
hpp::fcl::computeBV< OBB, Cone >
HPP_FCL_DLLAPI void computeBV< OBB, Cone >(const Cone &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:469
hpp::fcl::computeBV
void computeBV(const S &s, const Transform3f &tf, BV &bv)
calculate a bounding volume for a shape in a specific configuration
Definition: geometric_shapes_utility.h:74
hpp::fcl::computeBV< kIOS, Halfspace >
HPP_FCL_DLLAPI void computeBV< kIOS, Halfspace >(const Halfspace &s, const Transform3f &tf, kIOS &bv)
Definition: geometric_shapes_utility.cpp:527
hpp::fcl::computeBV< AABB, Cylinder >
HPP_FCL_DLLAPI void computeBV< AABB, Cylinder >(const Cylinder &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:333
hpp::fcl::computeBV< OBB, Cylinder >
HPP_FCL_DLLAPI void computeBV< OBB, Cylinder >(const Cylinder &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:479
hpp::fcl::fit
void fit(Vec3f *ps, unsigned int n, BV &bv)
Compute a bounding volume that fits a set of n points.
Definition: BV_fitter.h:52
hpp::fcl::computeBV< OBB, Capsule >
HPP_FCL_DLLAPI void computeBV< OBB, Capsule >(const Capsule &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:459
details
Definition: traversal_node_setup.h:792
hpp::fcl::computeBV< RSS, Plane >
HPP_FCL_DLLAPI void computeBV< RSS, Plane >(const Plane &s, const Transform3f &tf, RSS &bv)
Definition: geometric_shapes_utility.cpp:745
hpp::fcl::computeBV< OBB, ConvexBase >
HPP_FCL_DLLAPI void computeBV< OBB, ConvexBase >(const ConvexBase &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:490
hpp::fcl::computeBV< AABB, Ellipsoid >
HPP_FCL_DLLAPI void computeBV< AABB, Ellipsoid >(const Ellipsoid &e, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:294
hpp::fcl::constructBox
HPP_FCL_DLLAPI void constructBox(const AABB &bv, Box &box, Transform3f &tf)
construct a box shape (with a configuration) from a given bounding volume
Definition: geometric_shapes_utility.cpp:911
hpp::fcl::computeBV< AABB, Cone >
HPP_FCL_DLLAPI void computeBV< AABB, Cone >(const Cone &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:316
BV.h
hpp
Main namespace.
Definition: broadphase_bruteforce.h:44
hpp::fcl::computeBV< AABB, Halfspace >
HPP_FCL_DLLAPI void computeBV< AABB, Halfspace >(const Halfspace &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:372
hpp::fcl::computeBV< OBB, Box >
HPP_FCL_DLLAPI void computeBV< OBB, Box >(const Box &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:440
hpp::fcl::computeBV< OBB, Plane >
HPP_FCL_DLLAPI void computeBV< OBB, Plane >(const Plane &s, const Transform3f &tf, OBB &bv)
Definition: geometric_shapes_utility.cpp:731
hpp::fcl::computeBV< AABB, Plane >
HPP_FCL_DLLAPI void computeBV< AABB, Plane >(const Plane &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:405
hpp::fcl::computeBV< RSS, Halfspace >
HPP_FCL_DLLAPI void computeBV< RSS, Halfspace >(const Halfspace &s, const Transform3f &tf, RSS &bv)
Definition: geometric_shapes_utility.cpp:511
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::computeBV< kIOS, Plane >
HPP_FCL_DLLAPI void computeBV< kIOS, Plane >(const Plane &s, const Transform3f &tf, kIOS &bv)
Definition: geometric_shapes_utility.cpp:768
hpp::fcl::computeBV< AABB, ConvexBase >
HPP_FCL_DLLAPI void computeBV< AABB, ConvexBase >(const ConvexBase &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:351
hpp::fcl::computeBV< AABB, Capsule >
HPP_FCL_DLLAPI void computeBV< AABB, Capsule >(const Capsule &s, const Transform3f &tf, AABB &bv)
Definition: geometric_shapes_utility.cpp:305
geometric_shapes.h
hpp::fcl::computeBV< OBBRSS, Plane >
HPP_FCL_DLLAPI void computeBV< OBBRSS, Plane >(const Plane &s, const Transform3f &tf, OBBRSS &bv)
Definition: geometric_shapes_utility.cpp:761
BV_fitter.h
hpp::fcl::details::getBoundVertices
std::vector< Vec3f > getBoundVertices(const Box &box, const Transform3f &tf)
Definition: geometric_shapes_utility.cpp:47


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13