Skip to content

Commit

Permalink
Create default distance/collision callbacks in fcl namespace
Browse files Browse the repository at this point in the history
We had default callbacks defined in the test namespace. The main readme.md
was recommending using them. This moves them directly into fcl namespace
so that user code doesn't have to pull in test code.
  • Loading branch information
SeanCurtis-TRI committed Feb 4, 2020
1 parent a46c2af commit 0a83fa8
Show file tree
Hide file tree
Showing 10 changed files with 287 additions and 193 deletions.
7 changes: 6 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,12 @@
* Added distance request option for computing exact negative distance: [#172](https://github.com/flexible-collision-library/fcl/pull/172)

* Build/Test/Misc

* Default callback functions for broadphase collision managers have been moved
out of `fcl::test` and into `fcl` namespace (with a corresponding name
change, e.g., `defaultDistanceFunction` --> `DefaultDistanceFunction`).
[#438](https://github.com/flexible-collision-library/fcl/pull/438)
* This includes the removal of the stub function
`defaultContinuousDistanceFunction()`.
* Added version check for Visual Studio in CMake (VS2015 or greater required): [#189](https://github.com/flexible-collision-library/fcl/pull/189)
* Added CMake targets for generating API documentation: [#174](https://github.com/flexible-collision-library/fcl/pull/174)
* Enabled build with SSE option by default: [#159](https://github.com/flexible-collision-library/fcl/pull/159)
Expand Down
31 changes: 16 additions & 15 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -191,34 +191,35 @@ manager2->registerObjects(objects2);
// requires two settings:
// a) a callback to collision or distance;
// b) an intermediate data to store the information generated during the
// broadphase computation
// For a), FCL's test framework provides default callbacks for both collision
// and distance. For b), FCL uses the CollisionData structure for collision and
// DistanceData structure for distance. CollisionData/DistanceData is just a
// container from the test framework including both the
// CollisionRequest/DistanceRequest and CollisionResult/DistanceResult
// structures mentioned above.
CollisionData collision_data;
DistanceData distance_data;
// broadphase computation.
// For convenience, FCL provides default callbacks to satisfy a) and a
// corresponding call back data to satisfy b) for both collision and distance
// queries. For collision use DefaultCollisionCallback and DefaultCollisionData
// and for distance use DefaultDistanceCallback and DefaultDistanceData.
// The default collision/distance data structs are simply containers which
// include the request and distance structures for each query type as mentioned
// above.
DefaultCollisionData collision_data;
DefaultDistanceData distance_data;
// Setup the managers, which is related with initializing the broadphase
// acceleration structure according to objects input
manager1->setup();
manager2->setup();
// Examples for various queries
// 1. Collision query between two object groups and get collision numbers
manager2->collide(manager1, &collision_data, test::defaultCollisionFunction);
manager2->collide(manager1, &collision_data, DefaultCollisionFunction);
int n_contact_num = collision_data.result.numContacts();
// 2. Distance query between two object groups and get the minimum distance
manager2->distance(manager1, &distance_data, test::defaultDistanceFunction);
manager2->distance(manager1, &distance_data, DefaultDistanceFunction);
double min_distance = distance_data.result.min_distance;
// 3. Self collision query for group 1
manager1->collide(&collision_data, test::defaultCollisionFunction);
manager1->collide(&collision_data, DefaultCollisionFunction);
// 4. Self distance query for group 1
manager1->distance(&distance_data, test::defaultDistanceFunction);
manager1->distance(&distance_data, DefaultDistanceFunction);
// 5. Collision query between one object in group 1 and the entire group 2
manager2->collide(objects1[0], &collision_data, test::defaultCollisionFunction);
manager2->collide(objects1[0], &collision_data, DefaultCollisionFunction);
// 6. Distance query between one object in group 1 and the entire group 2
manager2->distance(objects1[0], &distance_data, test::defaultDistanceFunction);
manager2->distance(objects1[0], &distance_data, DefaultDistanceFunction);
```


Expand Down
219 changes: 219 additions & 0 deletions include/fcl/broadphase/default_broadphase_callbacks.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,219 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2020, Toyota Research Institute
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

/** @author Sean Curtis (sean@tri.global) */

#ifndef FCL_BROADPHASE_DEFAULTBROADPHASECALLBACKS_H
#define FCL_BROADPHASE_DEFAULTBROADPHASECALLBACKS_H

#include "fcl/narrowphase/collision.h"
#include "fcl/narrowphase/collision_request.h"
#include "fcl/narrowphase/collision_result.h"
#include "fcl/narrowphase/continuous_collision.h"
#include "fcl/narrowphase/continuous_collision_request.h"
#include "fcl/narrowphase/continuous_collision_result.h"
#include "fcl/narrowphase/distance.h"
#include "fcl/narrowphase/distance_request.h"
#include "fcl/narrowphase/distance_result.h"

namespace fcl {

/// @brief Collision data for use with the DefaultCollisionFunction. It stores
/// the collision request and the result given by collision algorithm (and
/// stores the conclusion of whether further evaluation of the broadphase
/// collision manager has been deemed unnecessary).
template <typename S>
struct DefaultCollisionData {
CollisionRequest<S> request;
CollisionResult<S> result;

/// If `true`, requests that the broadphase evaluation stop.
bool done{false};
};

/// @brief Provides a simple callback for the collision query in the
/// BroadPhaseCollisionManager. It assumes the `data` parameter is non-null and
/// points to an instance of DefaultCollisionData. It simply invokes the
/// `collide()` method on the culled pair of geometries and stores the results
/// in the data's CollisionResult instance.
///
/// This callback will cause the broadphase evaluation to stop if:
/// - the collision requests _disables_ cost _and_
/// - the collide() reports a collision for the culled pair, _and_
/// - we've reported the number of contacts requested in the CollisionRequest.
///
/// For a given instance of DefaultCollisionData, if broadphase evaluation has
/// already terminated (i.e., DefaultCollisionFunction() returned `true`),
/// subsequent invocations with the same instance of DefaultCollisionData will
/// return immediately, requesting termination of broadphase evaluation (i.e.,
/// return `true`).
///
/// @param o1 The first object in the culled pair.
/// @param o2 The second object in the culled pair.
/// @param data A non-null pointer to a DefaultCollisionData instance.
/// @return `true` if the broadphase evaluation should stop.
/// @tparam S The scalar type with which the computation will be performed.
template <typename S>
bool DefaultCollisionFunction(CollisionObject<S>* o1, CollisionObject<S>* o2,
void* data) {
assert(data != nullptr);
auto* collision_data = static_cast<DefaultCollisionData<S>*>(data);
const CollisionRequest<S>& request = collision_data->request;
CollisionResult<S>& result = collision_data->result;

if(collision_data->done) return true;

collide(o1, o2, request, result);

if (!request.enable_cost && result.isCollision() &&
result.numContacts() >= request.num_max_contacts) {
collision_data->done = true;
}

return collision_data->done;
}


/// @brief Collision data for use with the DefaultContinuousCollisionFunction.
/// It stores the collision request and the result given by the collision
/// algorithm (and stores the conclusion of whether further evaluation of the
/// broadphase collision manager has been deemed unnecessary).
template <typename S>
struct DefaultContinuousCollisionData {
ContinuousCollisionRequest<S> request;
ContinuousCollisionResult<S> result;

/// If `true`, requests that the broadphase evaluation stop.
bool done{false};
};


/// @brief Provides a simple callback for the continuous collision query in the
/// BroadPhaseCollisionManager. It assumes the `data` parameter is non-null and
/// points to an instance of DefaultContinuousCollisionData. It simply invokes
/// the `collide()` method on the culled pair of geometries and stores the
/// results in the data's ContinuousCollisionResult instance.
///
/// This callback will never cause the broadphase evaluation to terminate early.
/// However, if the `done` member of the DefaultContinuousCollisionData is set
/// to true, this method will simply return without doing any computation.
///
/// For a given instance of DefaultContinuousCollisionData, if broadphase
/// evaluation has already terminated (i.e.,
/// DefaultContinuousCollisionFunction() returned `true`), subsequent
/// invocations with the same instance of DefaultCollisionData will return
/// immediately, requesting termination of broadphase evaluation (i.e., return
/// `true`).
///
/// @param o1 The first object in the culled pair.
/// @param o2 The second object in the culled pair.
/// @param data A non-null pointer to a DefaultCollisionData instance.
/// @return True if the broadphase evaluation should stop.
/// @tparam S The scalar type with which the computation will be performed.
template <typename S>
bool DefaultContinuousCollisionFunction(ContinuousCollisionObject<S>* o1,
ContinuousCollisionObject<S>* o2,
void* data) {
assert(data != nullptr);
auto* cdata = static_cast<DefaultContinuousCollisionData<S>*>(data);

if (cdata->done) return true;

const ContinuousCollisionRequest<S>& request = cdata->request;
ContinuousCollisionResult<S>& result = cdata->result;
collide(o1, o2, request, result);

return cdata->done;
}

/// @brief Distance data for use with the DefaultDistanceFunction. It stores
/// the distance request and the result given by distance algorithm (and
/// stores the conclusion of whether further evaluation of the broadphase
/// collision manager has been deemed unnecessary).
template <typename S>
struct DefaultDistanceData {
DistanceRequest<S> request;
DistanceResult<S> result;

/// If `true`, requests that the broadphase evaluation stop.
bool done{false};
};

/// @brief Provides a simple callback for the distance query in the
/// BroadPhaseCollisionManager. It assumes the `data` parameter is non-null and
/// points to an instance of DefaultDistanceData. It simply invokes the
/// `distance()` method on the culled pair of geometries and stores the results
/// in the data's DistanceResult instance.
///
/// This callback will cause the broadphase evaluation to stop if:
/// - The distance is less than or equal to zero (i.e., the pair is in
/// contact).
///
/// For a given instance of DefaultDistanceData, if broadphase evaluation has
/// already terminated (i.e., DefaultDistanceFunction() returned `true`),
/// subsequent invocations with the same instance of DefaultDistanceData will
/// simply report the previously reported minimum distance and request
/// termination of broadphase evaluation (i.e., return `true`).
///
/// @param o1 The first object in the culled pair.
/// @param o2 The second object in the culled pair.
/// @param data A non-null pointer to a DefaultDistanceData instance.
/// @param dist The distance computed by distance().
/// @return `true` if the broadphase evaluation should stop.
/// @tparam S The scalar type with which the computation will be performed.
template <typename S>
bool DefaultDistanceFunction(CollisionObject<S>* o1, CollisionObject<S>* o2,
void* data, S& dist) {
assert(data != nullptr);
auto* cdata = static_cast<DefaultDistanceData<S>*>(data);
const DistanceRequest<S>& request = cdata->request;
DistanceResult<S>& result = cdata->result;

if (cdata->done) {
dist = result.min_distance;
return true;
}

distance(o1, o2, request, result);

dist = result.min_distance;

if (dist <= 0) return true; // in collision or in touch

return cdata->done;
}

} // namespace fcl

#endif // FCL_BROADPHASE_DEFAULTBROADPHASECALLBACKS_H
9 changes: 5 additions & 4 deletions test/test_fcl_broadphase_collision_1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include "fcl/broadphase/broadphase_interval_tree.h"
#include "fcl/broadphase/broadphase_dynamic_AABB_tree.h"
#include "fcl/broadphase/broadphase_dynamic_AABB_tree_array.h"
#include "fcl/broadphase/default_broadphase_callbacks.h"
#include "fcl/broadphase/detail/sparse_hash_table.h"
#include "fcl/broadphase/detail/spatial_hash.h"
#include "fcl/geometry/geometric_shape_to_BVH_model.h"
Expand Down Expand Up @@ -447,7 +448,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
ts[i].push_back(timers[i].getElapsedTime());
}

std::vector<test::CollisionData<S>> self_data(managers.size());
std::vector<DefaultCollisionData<S>> self_data(managers.size());
for(size_t i = 0; i < managers.size(); ++i)
{
if(exhaustive) self_data[i].request.num_max_contacts = 100000;
Expand All @@ -457,7 +458,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
for(size_t i = 0; i < managers.size(); ++i)
{
timers[i].start();
managers[i]->collide(&self_data[i], test::defaultCollisionFunction);
managers[i]->collide(&self_data[i], DefaultCollisionFunction);
timers[i].stop();
ts[i].push_back(timers[i].getElapsedTime());
}
Expand Down Expand Up @@ -488,7 +489,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s

for(size_t i = 0; i < query.size(); ++i)
{
std::vector<test::CollisionData<S>> query_data(managers.size());
std::vector<DefaultCollisionData<S>> query_data(managers.size());
for(size_t j = 0; j < query_data.size(); ++j)
{
if(exhaustive) query_data[j].request.num_max_contacts = 100000;
Expand All @@ -498,7 +499,7 @@ void broad_phase_update_collision_test(S env_scale, std::size_t env_size, std::s
for(size_t j = 0; j < query_data.size(); ++j)
{
timers[j].start();
managers[j]->collide(query[i], &query_data[j], test::defaultCollisionFunction);
managers[j]->collide(query[i], &query_data[j], DefaultCollisionFunction);
timers[j].stop();
ts[j].push_back(timers[j].getElapsedTime());
}
Expand Down
9 changes: 5 additions & 4 deletions test/test_fcl_broadphase_collision_2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include "fcl/broadphase/broadphase_interval_tree.h"
#include "fcl/broadphase/broadphase_dynamic_AABB_tree.h"
#include "fcl/broadphase/broadphase_dynamic_AABB_tree_array.h"
#include "fcl/broadphase/default_broadphase_callbacks.h"
#include "fcl/broadphase/detail/sparse_hash_table.h"
#include "fcl/broadphase/detail/spatial_hash.h"
#include "fcl/geometry/geometric_shape_to_BVH_model.h"
Expand Down Expand Up @@ -252,7 +253,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
ts[i].push_back(timers[i].getElapsedTime());
}

std::vector<test::CollisionData<S>> self_data(managers.size());
std::vector<DefaultCollisionData<S>> self_data(managers.size());
for(size_t i = 0; i < managers.size(); ++i)
{
if(exhaustive) self_data[i].request.num_max_contacts = 100000;
Expand All @@ -262,7 +263,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
for(size_t i = 0; i < managers.size(); ++i)
{
timers[i].start();
managers[i]->collide(&self_data[i], test::defaultCollisionFunction);
managers[i]->collide(&self_data[i], DefaultCollisionFunction);
timers[i].stop();
ts[i].push_back(timers[i].getElapsedTime());
}
Expand Down Expand Up @@ -292,7 +293,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q

for(size_t i = 0; i < query.size(); ++i)
{
std::vector<test::CollisionData<S>> query_data(managers.size());
std::vector<DefaultCollisionData<S>> query_data(managers.size());
for(size_t j = 0; j < query_data.size(); ++j)
{
if(exhaustive) query_data[j].request.num_max_contacts = 100000;
Expand All @@ -302,7 +303,7 @@ void broad_phase_collision_test(S env_scale, std::size_t env_size, std::size_t q
for(size_t j = 0; j < query_data.size(); ++j)
{
timers[j].start();
managers[j]->collide(query[i], &query_data[j], test::defaultCollisionFunction);
managers[j]->collide(query[i], &query_data[j], DefaultCollisionFunction);
timers[j].stop();
ts[j].push_back(timers[j].getElapsedTime());
}
Expand Down
Loading

0 comments on commit 0a83fa8

Please sign in to comment.