37 #include <BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h>
38 #include <BulletCollision/CollisionShapes/btShapeHull.h>
39 #include <BulletCollision/Gimpact/btGImpactShape.h>
49 (void)(collision_object_type);
51 const double* size = geom->
size;
52 btScalar a =
static_cast<btScalar
>(size[0] / 2);
53 btScalar b =
static_cast<btScalar
>(size[1] / 2);
54 btScalar c =
static_cast<btScalar
>(size[2] / 2);
56 return (
new btBoxShape(btVector3(a, b, c)));
61 (void)(collision_object_type);
63 return (
new btSphereShape(
static_cast<btScalar
>(geom->
radius)));
68 (void)(collision_object_type);
70 btScalar
r =
static_cast<btScalar
>(geom->
radius);
71 btScalar l =
static_cast<btScalar
>(geom->
length / 2);
72 return (
new btCylinderShapeZ(btVector3(r, r, l)));
77 (void)(collision_object_type);
79 btScalar
r =
static_cast<btScalar
>(geom->
radius);
80 btScalar l =
static_cast<btScalar
>(geom->
length);
81 return (
new btConeShapeZ(r, l));
85 CollisionObjectWrapper* cow)
94 switch (collision_object_type)
101 std::vector<int> faces;
110 btConvexHullShape* subshape =
new btConvexHullShape();
113 btVector3(
static_cast<btScalar
>(v[0]),
static_cast<btScalar
>(v[1]),
static_cast<btScalar
>(v[2])));
119 btCompoundShape* compound =
127 for (
unsigned x = 0;
x < 3; ++
x)
130 for (
unsigned y = 0;
y < 3; ++
y)
132 v[
x][
y] =
static_cast<btScalar
>(geom->
vertices[3 * idx +
y]);
136 btCollisionShape* subshape =
new btTriangleShapeEx(v[0], v[1], v[2]);
137 if (subshape !=
nullptr)
139 cow->manage(subshape);
141 btTransform geom_trans;
142 geom_trans.setIdentity();
143 compound->addChildShape(geom_trans, subshape);
151 ROS_ERROR(
"This bullet shape type (%d) is not supported for geometry meshs",
152 static_cast<int>(collision_object_type));
162 CollisionObjectWrapper* cow)
169 btCompoundShape* subshape =
171 double occupancy_threshold = geom->
octree->getOccupancyThres();
174 switch (collision_object_type)
178 for (
auto it = geom->
octree->begin(
static_cast<unsigned char>(geom->
octree->getTreeDepth())),
179 end = geom->
octree->end();
182 if (it->getOccupancy() >= occupancy_threshold)
184 double size = it.getSize();
185 btTransform geom_trans;
186 geom_trans.setIdentity();
187 geom_trans.setOrigin(btVector3(
static_cast<btScalar
>(it.getX()),
static_cast<btScalar
>(it.getY()),
188 static_cast<btScalar
>(it.getZ())));
189 btScalar l =
static_cast<btScalar
>(size / 2);
190 btBoxShape* childshape =
new btBoxShape(btVector3(l, l, l));
192 cow->manage(childshape);
194 subshape->addChildShape(geom_trans, childshape);
201 for (
auto it = geom->
octree->begin(
static_cast<unsigned char>(geom->
octree->getTreeDepth())),
202 end = geom->
octree->end();
205 if (it->getOccupancy() >= occupancy_threshold)
207 double size = it.getSize();
208 btTransform geom_trans;
209 geom_trans.setIdentity();
210 geom_trans.setOrigin(btVector3(
static_cast<btScalar
>(it.getX()),
static_cast<btScalar
>(it.getY()),
211 static_cast<btScalar
>(it.getZ())));
212 btSphereShape* childshape =
213 new btSphereShape(
static_cast<btScalar
>(std::sqrt(2 * ((size / 2) * (size / 2)))));
215 cow->manage(childshape);
217 subshape->addChildShape(geom_trans, childshape);
224 ROS_ERROR(
"This bullet shape type (%d) is not supported for geometry octree",
225 static_cast<int>(collision_object_type));
262 ROS_ERROR(
"This geometric shape type (%d) is not supported using BULLET yet",
static_cast<int>(geom->type));
269 const std::vector<shapes::ShapeConstPtr>&
shapes,
270 const AlignedVector<Eigen::Isometry3d>& shape_poses,
271 const std::vector<CollisionObjectType>& collision_object_types,
276 , m_shape_poses(shape_poses)
277 , m_collision_object_types(collision_object_types)
279 if (
shapes.empty() || shape_poses.empty() ||
280 (
shapes.size() != shape_poses.size() || collision_object_types.empty() ||
281 shapes.size() != collision_object_types.size()))
283 throw std::exception();
287 assert(!
name.empty());
291 m_collisionFilterGroup = btBroadphaseProxy::KinematicFilter;
292 m_collisionFilterMask = btBroadphaseProxy::KinematicFilter | btBroadphaseProxy::StaticFilter;
296 m_collisionFilterGroup = btBroadphaseProxy::StaticFilter;
297 m_collisionFilterMask = btBroadphaseProxy::KinematicFilter;
305 setCollisionShape(shape);
310 btCompoundShape* compound =
315 setCollisionShape(compound);
318 Eigen::Isometry3d inv_world = m_shape_poses[0].inverse();
320 for (std::size_t j = 0; j < m_shapes.size(); ++j)
322 btCollisionShape* subshape =
createShapePrimitive(m_shapes[j], collision_object_types[j],
this);
323 if (subshape !=
nullptr)
328 compound->addChildShape(geom_trans, subshape);
335 const std::vector<shapes::ShapeConstPtr>&
shapes,
336 const AlignedVector<Eigen::Isometry3d>& shape_poses,
337 const std::vector<CollisionObjectType>& collision_object_types,
338 const std::set<std::string>& touch_links)
339 : CollisionObjectWrapper(
name, type_id,
shapes, shape_poses, collision_object_types, true)
345 const std::vector<shapes::ShapeConstPtr>&
shapes,
346 const AlignedVector<Eigen::Isometry3d>& shape_poses,
347 const std::vector<CollisionObjectType>& collision_object_types,
348 const std::vector<std::shared_ptr<void>>& data)
352 , m_shape_poses(shape_poses)
353 , m_collision_object_types(collision_object_types)