Skip to content

Commit 165c381

Browse files
committed
Update to hpp-fcl devel branch
1 parent 8f455c5 commit 165c381

File tree

2 files changed

+16
-13
lines changed

2 files changed

+16
-13
lines changed

dependencies.repos

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
- git:
1414
local-name: hpp-fcl
1515
uri: https://github.com/humanoid-path-planner/hpp-fcl.git
16-
version: v2.4.1
16+
version: devel
1717
- git:
1818
local-name: octomap
1919
uri: https://github.com/OctoMap/octomap.git

tesseract_collision/hpp_fcl/src/hpp_fcl_utils.cpp

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -117,26 +117,28 @@ CollisionGeometryPtr createShapePrimitive(const tesseract_geometry::ConvexMesh::
117117
{
118118
int vertex_count = geom->getVertexCount();
119119
int triangle_count = geom->getFaceCount();
120-
const tesseract_common::VectorVector3d& vertices = *(geom->getVertices());
121120
const Eigen::VectorXi& triangles = *(geom->getFaces());
122121

123122
if (vertex_count > 0 && triangle_count > 0)
124123
{
125-
std::vector<hpp::fcl::Triangle> tri_indices(static_cast<size_t>(triangle_count));
124+
// TODO: This is just a copy to get rid of the constness
125+
auto vertices = std::make_shared<std::vector<hpp::fcl::Vec3f>>(static_cast<size_t>(vertex_count));
126+
for (int i = 0; i < vertex_count; ++i)
127+
{
128+
vertices->at(static_cast<size_t>(i)) = geom->getVertices()->at(i);
129+
}
130+
131+
auto tri_indices = std::make_shared<std::vector<hpp::fcl::Triangle>>(static_cast<size_t>(triangle_count));
126132
for (int i = 0; i < triangle_count; ++i)
127133
{
128134
assert(triangles[4L * i] == 3);
129-
tri_indices[static_cast<size_t>(i)] = hpp::fcl::Triangle(static_cast<size_t>(triangles[(4 * i) + 1]),
130-
static_cast<size_t>(triangles[(4 * i) + 2]),
131-
static_cast<size_t>(triangles[(4 * i) + 3]));
135+
tri_indices->at(static_cast<size_t>(i)) = hpp::fcl::Triangle(static_cast<size_t>(triangles[(4 * i) + 1]),
136+
static_cast<size_t>(triangles[(4 * i) + 2]),
137+
static_cast<size_t>(triangles[(4 * i) + 3]));
132138
}
133139

134-
return CollisionGeometryPtr(new hpp::fcl::Convex<hpp::fcl::Triangle>(
135-
false,
136-
const_cast<Eigen::Matrix<double, 3, 1>*>(geom->getVertices()->data()), // NOLINT
137-
vertex_count,
138-
tri_indices.data(),
139-
triangle_count));
140+
return CollisionGeometryPtr(
141+
new hpp::fcl::Convex<hpp::fcl::Triangle>(vertices, vertex_count, tri_indices, triangle_count));
140142
}
141143

142144
CONSOLE_BRIDGE_logError("The mesh is empty!");
@@ -326,7 +328,8 @@ bool DistanceCollisionCallback::collide(hpp::fcl::CollisionObject* o1, hpp::fcl:
326328
contact.type_id[0] = cd1->getTypeID();
327329
contact.type_id[1] = cd2->getTypeID();
328330
contact.distance = fcl_result.min_distance;
329-
contact.normal = (fcl_result.min_distance * (contact.nearest_points[1] - contact.nearest_points[0])).normalized();
331+
// contact.normal = (fcl_result.min_distance * (contact.nearest_points[1] - contact.nearest_points[0])).normalized();
332+
contact.normal = fcl_result.normal;
330333

331334
ObjectPairKey pc = tesseract_common::makeOrderedLinkPair(cd1->getName(), cd2->getName());
332335
const auto it = cdata->res->find(pc);

0 commit comments

Comments
 (0)