drake icon indicating copy to clipboard operation
drake copied to clipboard

Signed distance calculation against concave triangle meshes

Open gizatt opened this issue 8 years ago • 4 comments

A feature I'm finding myself in great need of is the ability to call a function that operates like collisionDetectFromPoints, but on a concave mesh. Specifically, I need the ability to load in a mesh from a .obj file and query the shortest distance from a point to the surface of the mesh, with the distance having negative sign if the point is inside the mesh. (Having this functionality wrapped up to the level of a RigidBodyTree would be nice but not necessary.)

Before I go trying to twist the collision code to try to support this, is this feature in the roadmap / in progress by anyone? Any advice on a minimum-energy way to get this working?

@amcastro-tri maybe?

gizatt avatar Aug 23 '16 04:08 gizatt

We have now the capability to load static meshes. You can see a very simple test here. We do not have yet the capability to do the same for dynamically moving triangle meshes. Usually we simplify concave geometries as the union of several convex geometries by having a link with several convex collision elements. That might be enough for your application as a simple workaround.

amcastro-tri avatar Aug 23 '16 15:08 amcastro-tri

Related to #9779

RussTedrake avatar Nov 11 '18 15:11 RussTedrake

Refresh; we're still missing this. Even though we have partial support for Convex (e.g., interaction) we don't have support for signed distance to point.

One could hack it by registering a zero-radius sphere for the query point. and then calling QueryObject::ComputeSignedDistancePairClosestPoints(). But actual support for the primitive would be better.

SeanCurtis-TRI avatar May 14 '20 17:05 SeanCurtis-TRI

This feature has come up again in the context of #14431, as parts of our collision checking pipeline require point signed distance queries and thus do not currently support mesh geometries. Specifically:

  1. The "MbpEnvironment" collision checker performs point signed distance queries against geometries belonging to the environment.
  2. The environment voxelizer uses point signed distance queries to build dense occupancy grids (in parallel, without having to use multiple contexts or add dummy geometry).

calderpg-tri avatar Aug 11 '22 22:08 calderpg-tri

We have the functionality to compute unsigned distance from a point to a triangular mesh (that's how we make hydro pressure fields for potentially non-convex meshes) here: https://github.com/RobotLocomotion/drake/blob/b9813a712454580cd6bc0724f8d2506d85412e58/geometry/proximity/calc_distance_to_surface_mesh.h#L14

I would like to see QueryObject::ComputeSignedDistanceToPoint() to support all shapes. Right now support for Convex and Mesh is missing. The tricky part is doing in/out tests for .obj files, especially when there's no guarantee that the surface is even closed.

xuchenhan-tri avatar Jun 26 '23 20:06 xuchenhan-tri

This is a relevant paper: J.A. Baerentzen; H. Aanaes. Signed distance computation using the angle weighted pseudonormal. IEEE Transactions on Visualization and Computer Graphics ( Volume: 11, Issue: 3, May-June 2005)

They use angle-weighted pseudonormals of the closest features (vertex, edge, or triangle) to do in/out tests with the assumption that we have vertex-to-triangle and edge-to-triangle information. (It doesn't work with triangle soups.)

DamrongGuoy avatar Jun 27 '23 02:06 DamrongGuoy