DART 6.12.2
Loading...
Searching...
No Matches
CollisionShapes.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2021, The DART development contributors
3 * All rights reserved.
4 *
5 * The list of contributors can be found at:
6 * https://github.com/dartsim/dart/blob/master/LICENSE
7 *
8 * This file is provided under the following "BSD-style" License:
9 * Redistribution and use in source and binary forms, with or
10 * without modification, are permitted provided that the following
11 * conditions are met:
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 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19 * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20 * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24 * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26 * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 */
32
33#ifndef DART_COLLISION_FCL_MESH_COLLISIONSHAPES_HPP_
34#define DART_COLLISION_FCL_MESH_COLLISIONSHAPES_HPP_
35
36#include <cmath>
37
38#include <assimp/scene.h>
39
42
43namespace dart {
44namespace collision {
45
46template <class BV>
48 float _scaleX,
49 float _scaleY,
50 float _scaleZ,
51 const aiScene* _mesh,
52 const dart::collision::fcl::Transform3& _transform)
53{
54 assert(_mesh);
55 ::fcl::BVHModel<BV>* model = new ::fcl::BVHModel<BV>;
56 model->beginModel();
57
58 for (unsigned int i = 0; i < _mesh->mNumMeshes; i++)
59 {
60 for (unsigned int j = 0; j < _mesh->mMeshes[i]->mNumFaces; j++)
61 {
63 for (unsigned int k = 0; k < 3; k++)
64 {
65 const aiVector3D& vertex
66 = _mesh->mMeshes[i]
67 ->mVertices[_mesh->mMeshes[i]->mFaces[j].mIndices[k]];
69 vertex.x * _scaleX, vertex.y * _scaleY, vertex.z * _scaleZ);
70 vertices[k] = dart::collision::fcl::transform(_transform, vertices[k]);
71 }
72 model->addTriangle(vertices[0], vertices[1], vertices[2]);
73 }
74 }
75
76 model->endModel();
77 return model;
78}
79
80template <class BV>
82 float _sizeX,
83 float _sizeY,
84 float _sizeZ,
85 const dart::collision::fcl::Transform3& _transform)
86{
87 float v[59][3] = {{0, 0, 0},
88 {0.135299, -0.461940, -0.135299},
89 {0.000000, -0.461940, -0.191342},
90 {-0.135299, -0.461940, -0.135299},
91 {-0.191342, -0.461940, 0.000000},
92 {-0.135299, -0.461940, 0.135299},
93 {0.000000, -0.461940, 0.191342},
94 {0.135299, -0.461940, 0.135299},
95 {0.191342, -0.461940, 0.000000},
96 {0.250000, -0.353553, -0.250000},
97 {0.000000, -0.353553, -0.353553},
98 {-0.250000, -0.353553, -0.250000},
99 {-0.353553, -0.353553, 0.000000},
100 {-0.250000, -0.353553, 0.250000},
101 {0.000000, -0.353553, 0.353553},
102 {0.250000, -0.353553, 0.250000},
103 {0.353553, -0.353553, 0.000000},
104 {0.326641, -0.191342, -0.326641},
105 {0.000000, -0.191342, -0.461940},
106 {-0.326641, -0.191342, -0.326641},
107 {-0.461940, -0.191342, 0.000000},
108 {-0.326641, -0.191342, 0.326641},
109 {0.000000, -0.191342, 0.461940},
110 {0.326641, -0.191342, 0.326641},
111 {0.461940, -0.191342, 0.000000},
112 {0.353553, 0.000000, -0.353553},
113 {0.000000, 0.000000, -0.500000},
114 {-0.353553, 0.000000, -0.353553},
115 {-0.500000, 0.000000, 0.000000},
116 {-0.353553, 0.000000, 0.353553},
117 {0.000000, 0.000000, 0.500000},
118 {0.353553, 0.000000, 0.353553},
119 {0.500000, 0.000000, 0.000000},
120 {0.326641, 0.191342, -0.326641},
121 {0.000000, 0.191342, -0.461940},
122 {-0.326641, 0.191342, -0.326641},
123 {-0.461940, 0.191342, 0.000000},
124 {-0.326641, 0.191342, 0.326641},
125 {0.000000, 0.191342, 0.461940},
126 {0.326641, 0.191342, 0.326641},
127 {0.461940, 0.191342, 0.000000},
128 {0.250000, 0.353553, -0.250000},
129 {0.000000, 0.353553, -0.353553},
130 {-0.250000, 0.353553, -0.250000},
131 {-0.353553, 0.353553, 0.000000},
132 {-0.250000, 0.353553, 0.250000},
133 {0.000000, 0.353553, 0.353553},
134 {0.250000, 0.353553, 0.250000},
135 {0.353553, 0.353553, 0.000000},
136 {0.135299, 0.461940, -0.135299},
137 {0.000000, 0.461940, -0.191342},
138 {-0.135299, 0.461940, -0.135299},
139 {-0.191342, 0.461940, 0.000000},
140 {-0.135299, 0.461940, 0.135299},
141 {0.000000, 0.461940, 0.191342},
142 {0.135299, 0.461940, 0.135299},
143 {0.191342, 0.461940, 0.000000},
144 {0.000000, -0.500000, 0.000000},
145 {0.000000, 0.500000, 0.000000}};
146 int f[112][3]
147 = {{1, 2, 9}, {9, 2, 10}, {2, 3, 10}, {10, 3, 11}, {3, 4, 11},
148 {11, 4, 12}, {4, 5, 12}, {12, 5, 13}, {5, 6, 13}, {13, 6, 14},
149 {6, 7, 14}, {14, 7, 15}, {7, 8, 15}, {15, 8, 16}, {8, 1, 16},
150 {16, 1, 9}, {9, 10, 17}, {17, 10, 18}, {10, 11, 18}, {18, 11, 19},
151 {11, 12, 19}, {19, 12, 20}, {12, 13, 20}, {20, 13, 21}, {13, 14, 21},
152 {21, 14, 22}, {14, 15, 22}, {22, 15, 23}, {15, 16, 23}, {23, 16, 24},
153 {16, 9, 24}, {24, 9, 17}, {17, 18, 25}, {25, 18, 26}, {18, 19, 26},
154 {26, 19, 27}, {19, 20, 27}, {27, 20, 28}, {20, 21, 28}, {28, 21, 29},
155 {21, 22, 29}, {29, 22, 30}, {22, 23, 30}, {30, 23, 31}, {23, 24, 31},
156 {31, 24, 32}, {24, 17, 32}, {32, 17, 25}, {25, 26, 33}, {33, 26, 34},
157 {26, 27, 34}, {34, 27, 35}, {27, 28, 35}, {35, 28, 36}, {28, 29, 36},
158 {36, 29, 37}, {29, 30, 37}, {37, 30, 38}, {30, 31, 38}, {38, 31, 39},
159 {31, 32, 39}, {39, 32, 40}, {32, 25, 40}, {40, 25, 33}, {33, 34, 41},
160 {41, 34, 42}, {34, 35, 42}, {42, 35, 43}, {35, 36, 43}, {43, 36, 44},
161 {36, 37, 44}, {44, 37, 45}, {37, 38, 45}, {45, 38, 46}, {38, 39, 46},
162 {46, 39, 47}, {39, 40, 47}, {47, 40, 48}, {40, 33, 48}, {48, 33, 41},
163 {41, 42, 49}, {49, 42, 50}, {42, 43, 50}, {50, 43, 51}, {43, 44, 51},
164 {51, 44, 52}, {44, 45, 52}, {52, 45, 53}, {45, 46, 53}, {53, 46, 54},
165 {46, 47, 54}, {54, 47, 55}, {47, 48, 55}, {55, 48, 56}, {48, 41, 56},
166 {56, 41, 49}, {2, 1, 57}, {3, 2, 57}, {4, 3, 57}, {5, 4, 57},
167 {6, 5, 57}, {7, 6, 57}, {8, 7, 57}, {1, 8, 57}, {49, 50, 58},
168 {50, 51, 58}, {51, 52, 58}, {52, 53, 58}, {53, 54, 58}, {54, 55, 58},
169 {55, 56, 58}, {56, 49, 58}};
170
171 ::fcl::BVHModel<BV>* model = new ::fcl::BVHModel<BV>;
173 model->beginModel();
174
175 for (int i = 0; i < 112; i++)
176 {
178 v[f[i][0]][0] * _sizeX, v[f[i][0]][1] * _sizeY, v[f[i][0]][2] * _sizeZ);
180 v[f[i][1]][0] * _sizeX, v[f[i][1]][1] * _sizeY, v[f[i][1]][2] * _sizeZ);
182 v[f[i][2]][0] * _sizeX, v[f[i][2]][1] * _sizeY, v[f[i][2]][2] * _sizeZ);
183 p1 = dart::collision::fcl::transform(_transform, p1);
184 p2 = dart::collision::fcl::transform(_transform, p2);
185 p3 = dart::collision::fcl::transform(_transform, p3);
186 model->addTriangle(p1, p2, p3);
187 }
188 model->endModel();
189 return model;
190}
191
192// Create a cube mesh for collision detection
193template <class BV>
195 float _sizeX,
196 float _sizeY,
197 float _sizeZ,
198 const dart::collision::fcl::Transform3& _transform)
199{
200 // float n[6][3] = {
201 // {-1.0, 0.0, 0.0},
202 // {0.0, 1.0, 0.0},
203 // {1.0, 0.0, 0.0},
204 // {0.0, -1.0, 0.0},
205 // {0.0, 0.0, 1.0},
206 // {0.0, 0.0, -1.0}
207 // };
208 int faces[6][4] = {{0, 1, 2, 3},
209 {3, 2, 6, 7},
210 {7, 6, 5, 4},
211 {4, 5, 1, 0},
212 {5, 6, 2, 1},
213 {7, 4, 0, 3}};
214 float v[8][3];
215
216 v[0][0] = v[1][0] = v[2][0] = v[3][0] = -_sizeX / 2;
217 v[4][0] = v[5][0] = v[6][0] = v[7][0] = _sizeX / 2;
218 v[0][1] = v[1][1] = v[4][1] = v[5][1] = -_sizeY / 2;
219 v[2][1] = v[3][1] = v[6][1] = v[7][1] = _sizeY / 2;
220 v[0][2] = v[3][2] = v[4][2] = v[7][2] = -_sizeZ / 2;
221 v[1][2] = v[2][2] = v[5][2] = v[6][2] = _sizeZ / 2;
222
223 ::fcl::BVHModel<BV>* model = new ::fcl::BVHModel<BV>;
225 model->beginModel();
226
227 for (int i = 0; i < 6; i++)
228 {
230 v[faces[i][0]][0], v[faces[i][0]][1], v[faces[i][0]][2]);
232 v[faces[i][1]][0], v[faces[i][1]][1], v[faces[i][1]][2]);
234 v[faces[i][2]][0], v[faces[i][2]][1], v[faces[i][2]][2]);
235 p1 = dart::collision::fcl::transform(_transform, p1);
236 p2 = dart::collision::fcl::transform(_transform, p2);
237 p3 = dart::collision::fcl::transform(_transform, p3);
238 model->addTriangle(p1, p2, p3);
240 v[faces[i][0]][0], v[faces[i][0]][1], v[faces[i][0]][2]);
242 v[faces[i][2]][0], v[faces[i][2]][1], v[faces[i][2]][2]);
244 v[faces[i][3]][0], v[faces[i][3]][1], v[faces[i][3]][2]);
245 p1 = dart::collision::fcl::transform(_transform, p1);
246 p2 = dart::collision::fcl::transform(_transform, p2);
247 p3 = dart::collision::fcl::transform(_transform, p3);
248 model->addTriangle(p1, p2, p3);
249 }
250 model->endModel();
251 return model;
252}
253
254template <class BV>
256 double _baseRadius,
257 double _topRadius,
258 double _height,
259 int _slices,
260 int _stacks,
261 const dart::collision::fcl::Transform3& _transform)
262{
263 const int CACHE_SIZE = 240;
264
265 int i, j;
266 float sinCache[CACHE_SIZE];
267 float cosCache[CACHE_SIZE];
268 float angle;
269 float zBase;
270 float zLow, zHigh;
271 float sintemp, costemp;
272 float deltaRadius;
273 float radiusLow, radiusHigh;
274
275 if (_slices >= CACHE_SIZE)
276 _slices = CACHE_SIZE - 1;
277
278 if (_slices < 2 || _stacks < 1 || _baseRadius < 0.0 || _topRadius < 0.0
279 || _height < 0.0)
280 {
281 return nullptr;
282 }
283
284 /* Center at CoM */
285 zBase = -_height / 2;
286
287 /* Compute delta */
288 deltaRadius = _baseRadius - _topRadius;
289
290 /* Cache is the vertex locations cache */
291 for (i = 0; i < _slices; i++)
292 {
293 angle = 2 * math::constantsd::pi() * i / _slices;
294 sinCache[i] = sin(angle);
295 cosCache[i] = cos(angle);
296 }
297
298 sinCache[_slices] = sinCache[0];
299 cosCache[_slices] = cosCache[0];
300
301 ::fcl::BVHModel<BV>* model = new ::fcl::BVHModel<BV>;
302 dart::collision::fcl::Vector3 p1, p2, p3, p4;
303
304 model->beginModel();
305
306 /* Base of cylinder */
307 sintemp = sinCache[0];
308 costemp = cosCache[0];
309 radiusLow = _baseRadius;
310 zLow = zBase;
312 radiusLow * sintemp, radiusLow * costemp, zLow);
313 p1 = dart::collision::fcl::transform(_transform, p1);
314 for (i = 1; i < _slices; i++)
315 {
317 radiusLow * sinCache[i], radiusLow * cosCache[i], zLow);
319 radiusLow * sinCache[i + 1], radiusLow * cosCache[i + 1], zLow);
320 p2 = dart::collision::fcl::transform(_transform, p2);
321 p3 = dart::collision::fcl::transform(_transform, p3);
322 model->addTriangle(p1, p2, p3);
323
324 Eigen::Vector3d v(radiusLow * sinCache[i], radiusLow * cosCache[i], zLow);
325 }
326
327 /* Body of cylinder */
328 for (i = 0; i < _slices; i++)
329 {
330 for (j = 0; j < _stacks; j++)
331 {
332 zLow = j * _height / _stacks + zBase;
333 zHigh = (j + 1) * _height / _stacks + zBase;
334 radiusLow = _baseRadius - deltaRadius * (static_cast<float>(j) / _stacks);
335 radiusHigh
336 = _baseRadius - deltaRadius * (static_cast<float>(j + 1) / _stacks);
337
339 radiusLow * sinCache[i], radiusLow * cosCache[i], zLow);
341 radiusLow * sinCache[i + 1], radiusLow * cosCache[i + 1], zLow);
343 radiusHigh * sinCache[i], radiusHigh * cosCache[i], zHigh);
345 radiusHigh * sinCache[i + 1], radiusHigh * cosCache[i + 1], zHigh);
346 p1 = dart::collision::fcl::transform(_transform, p1);
347 p2 = dart::collision::fcl::transform(_transform, p2);
348 p3 = dart::collision::fcl::transform(_transform, p3);
349 p4 = dart::collision::fcl::transform(_transform, p4);
350
351 model->addTriangle(p1, p2, p3);
352 model->addTriangle(p2, p3, p4);
353 }
354 }
355
356 /* Top of cylinder */
357 sintemp = sinCache[0];
358 costemp = cosCache[0];
359 radiusLow = _topRadius;
360 zLow = zBase + _height;
362 radiusLow * sintemp, radiusLow * costemp, zLow);
363 p1 = dart::collision::fcl::transform(_transform, p1);
364 for (i = 1; i < _slices; i++)
365 {
367 radiusLow * sinCache[i], radiusLow * cosCache[i], zLow);
369 radiusLow * sinCache[i + 1], radiusLow * cosCache[i + 1], zLow);
370 p2 = dart::collision::fcl::transform(_transform, p2);
371 p3 = dart::collision::fcl::transform(_transform, p3);
372 model->addTriangle(p1, p2, p3);
373 }
374
375 model->endModel();
376 return model;
377}
378
379} // namespace collision
380} // namespace dart
381
382#endif // DART_COLLISION_FCL_MESH_COLLISIONSHAPES_HPP_
::fcl::Vec3f Vector3
Definition BackwardCompatibility.hpp:148
dart::collision::fcl::Vector3 transform(const dart::collision::fcl::Transform3 &t, const dart::collision::fcl::Vector3 &v)
Transforms a 3-dim vector by a transform and returns the result.
Definition BackwardCompatibility.cpp:133
::fcl::Transform3f Transform3
Definition BackwardCompatibility.hpp:150
::fcl::BVHModel< BV > * createMesh(float _scaleX, float _scaleY, float _scaleZ, const aiScene *_mesh, const dart::collision::fcl::Transform3 &_transform)
Definition CollisionShapes.hpp:47
::fcl::BVHModel< BV > * createCube(float _sizeX, float _sizeY, float _sizeZ, const dart::collision::fcl::Transform3 &_transform)
Definition CollisionShapes.hpp:194
::fcl::BVHModel< BV > * createEllipsoid(float _sizeX, float _sizeY, float _sizeZ, const dart::collision::fcl::Transform3 &_transform)
Definition CollisionShapes.hpp:81
::fcl::BVHModel< BV > * createCylinder(double _baseRadius, double _topRadius, double _height, int _slices, int _stacks, const dart::collision::fcl::Transform3 &_transform)
Definition CollisionShapes.hpp:255
Definition BulletCollisionDetector.cpp:60
static constexpr T pi()
Definition Constants.hpp:44