Skip to content

Commit c9079e9

Browse files
authored
Backport to Humble: Pass more distance information out from FCL collision check #2572 (#2979)
1 parent d583c04 commit c9079e9

File tree

2 files changed

+97
-85
lines changed

2 files changed

+97
-85
lines changed

moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h

Lines changed: 89 additions & 85 deletions
Original file line numberDiff line numberDiff line change
@@ -141,91 +141,6 @@ struct CostSource
141141
}
142142
};
143143

144-
/** \brief Representation of a collision checking result */
145-
struct CollisionResult
146-
{
147-
CollisionResult() : collision(false), distance(std::numeric_limits<double>::max()), contact_count(0)
148-
{
149-
}
150-
using ContactMap = std::map<std::pair<std::string, std::string>, std::vector<Contact> >;
151-
152-
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
153-
154-
/** \brief Clear a previously stored result */
155-
void clear()
156-
{
157-
collision = false;
158-
distance = std::numeric_limits<double>::max();
159-
contact_count = 0;
160-
contacts.clear();
161-
cost_sources.clear();
162-
}
163-
164-
/** \brief Throttled warning printing the first collision pair, if any. All collisions are logged at DEBUG level */
165-
void print() const;
166-
167-
/** \brief True if collision was found, false otherwise */
168-
bool collision;
169-
170-
/** \brief Closest distance between two bodies */
171-
double distance;
172-
173-
/** \brief Number of contacts returned */
174-
std::size_t contact_count;
175-
176-
/** \brief A map returning the pairs of body ids in contact, plus their contact details */
177-
ContactMap contacts;
178-
179-
/** \brief These are the individual cost sources when costs are computed */
180-
std::set<CostSource> cost_sources;
181-
};
182-
183-
/** \brief Representation of a collision checking request */
184-
struct CollisionRequest
185-
{
186-
CollisionRequest()
187-
: distance(false)
188-
, cost(false)
189-
, contacts(false)
190-
, max_contacts(1)
191-
, max_contacts_per_pair(1)
192-
, max_cost_sources(1)
193-
, verbose(false)
194-
{
195-
}
196-
virtual ~CollisionRequest()
197-
{
198-
}
199-
200-
/** \brief The group name to check collisions for (optional; if empty, assume the complete robot) */
201-
std::string group_name;
202-
203-
/** \brief If true, compute proximity distance */
204-
bool distance;
205-
206-
/** \brief If true, a collision cost is computed */
207-
bool cost;
208-
209-
/** \brief If true, compute contacts. Otherwise only a binary collision yes/no is reported. */
210-
bool contacts;
211-
212-
/** \brief Overall maximum number of contacts to compute */
213-
std::size_t max_contacts;
214-
215-
/** \brief Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at different
216-
* configurations) */
217-
std::size_t max_contacts_per_pair;
218-
219-
/** \brief When costs are computed, this value defines how many of the top cost sources should be returned */
220-
std::size_t max_cost_sources;
221-
222-
/** \brief Function call that decides whether collision detection should stop. */
223-
std::function<bool(const CollisionResult&)> is_done;
224-
225-
/** \brief Flag indicating whether information about detected collisions should be reported */
226-
bool verbose;
227-
};
228-
229144
namespace DistanceRequestTypes
230145
{
231146
enum DistanceRequestType
@@ -381,4 +296,93 @@ struct DistanceResult
381296
distances.clear();
382297
}
383298
};
299+
300+
/** \brief Representation of a collision checking result */
301+
struct CollisionResult
302+
{
303+
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
304+
305+
/** \brief Clear a previously stored result */
306+
void clear()
307+
{
308+
collision = false;
309+
distance = std::numeric_limits<double>::max();
310+
distance_result.clear();
311+
contact_count = 0;
312+
contacts.clear();
313+
cost_sources.clear();
314+
}
315+
316+
/** \brief Throttled warning printing the first collision pair, if any. All collisions are logged at DEBUG level */
317+
void print() const;
318+
319+
/** \brief True if collision was found, false otherwise */
320+
bool collision = false;
321+
322+
/** \brief Closest distance between two bodies */
323+
double distance = std::numeric_limits<double>::max();
324+
325+
/** \brief Distance data for each link */
326+
DistanceResult distance_result;
327+
328+
/** \brief Number of contacts returned */
329+
std::size_t contact_count = 0;
330+
331+
/** \brief A map returning the pairs of body ids in contact, plus their contact details */
332+
using ContactMap = std::map<std::pair<std::string, std::string>, std::vector<Contact> >;
333+
ContactMap contacts;
334+
335+
/** \brief These are the individual cost sources when costs are computed */
336+
std::set<CostSource> cost_sources;
337+
};
338+
339+
/** \brief Representation of a collision checking request */
340+
struct CollisionRequest
341+
{
342+
CollisionRequest()
343+
: distance(false)
344+
, cost(false)
345+
, contacts(false)
346+
, max_contacts(1)
347+
, max_contacts_per_pair(1)
348+
, max_cost_sources(1)
349+
, verbose(false)
350+
{
351+
}
352+
virtual ~CollisionRequest()
353+
{
354+
}
355+
356+
/** \brief The group name to check collisions for (optional; if empty, assume the complete robot) */
357+
std::string group_name;
358+
359+
/** \brief If true, compute proximity distance */
360+
bool distance;
361+
362+
/** \brief If true, return detailed distance information. Distance must be set to true as well */
363+
bool detailed_distance = false;
364+
365+
/** \brief If true, a collision cost is computed */
366+
bool cost;
367+
368+
/** \brief If true, compute contacts. Otherwise only a binary collision yes/no is reported. */
369+
bool contacts;
370+
371+
/** \brief Overall maximum number of contacts to compute */
372+
std::size_t max_contacts;
373+
374+
/** \brief Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at different
375+
* configurations) */
376+
std::size_t max_contacts_per_pair;
377+
378+
/** \brief When costs are computed, this value defines how many of the top cost sources should be returned */
379+
std::size_t max_cost_sources;
380+
381+
/** \brief Function call that decides whether collision detection should stop. */
382+
std::function<bool(const CollisionResult&)> is_done;
383+
384+
/** \brief Flag indicating whether information about detected collisions should be reported */
385+
bool verbose;
386+
};
387+
384388
} // namespace collision_detection

moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -277,6 +277,10 @@ void CollisionEnvFCL::checkSelfCollisionHelper(const CollisionRequest& req, Coll
277277
dreq.enableGroup(getRobotModel());
278278
distanceSelf(dreq, dres, state);
279279
res.distance = dres.minimum_distance.distance;
280+
if (req.detailed_distance)
281+
{
282+
res.distance_result = dres;
283+
}
280284
}
281285
}
282286

@@ -330,6 +334,10 @@ void CollisionEnvFCL::checkRobotCollisionHelper(const CollisionRequest& req, Col
330334
dreq.enableGroup(getRobotModel());
331335
distanceRobot(dreq, dres, state);
332336
res.distance = dres.minimum_distance.distance;
337+
if (req.detailed_distance)
338+
{
339+
res.distance_result = dres;
340+
}
333341
}
334342
}
335343

0 commit comments

Comments
 (0)