Skip to content

Commit

Permalink
Add ContactAllowedValidator and ContactResultValidator (#1095)
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong authored Jan 4, 2025
1 parent 16a4193 commit 11d935b
Show file tree
Hide file tree
Showing 56 changed files with 682 additions and 244 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -125,9 +125,10 @@ class BulletCastBVHManager : public ContinuousContactManager

const CollisionMarginData& getCollisionMarginData() const override final;

void setIsContactAllowedFn(IsContactAllowedFn fn) override final;
void
setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) override final;

IsContactAllowedFn getIsContactAllowedFn() const override final;
std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const override final;

void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -125,9 +125,10 @@ class BulletCastSimpleManager : public ContinuousContactManager
const std::string& name2,
double collision_margin) override final;

void setIsContactAllowedFn(IsContactAllowedFn fn) override final;
void
setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) override final;

IsContactAllowedFn getIsContactAllowedFn() const override final;
std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const override final;

void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,9 +114,10 @@ class BulletDiscreteBVHManager : public DiscreteContactManager

const CollisionMarginData& getCollisionMarginData() const override final;

void setIsContactAllowedFn(IsContactAllowedFn fn) override final;
void
setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) override final;

IsContactAllowedFn getIsContactAllowedFn() const override final;
std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const override final;

void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,9 +114,10 @@ class BulletDiscreteSimpleManager : public DiscreteContactManager

const CollisionMarginData& getCollisionMarginData() const override final;

void setIsContactAllowedFn(IsContactAllowedFn fn) override final;
void
setContactAllowedValidator(std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator) override final;

IsContactAllowedFn getIsContactAllowedFn() const override final;
std::shared_ptr<const tesseract_common::ContactAllowedValidator> getContactAllowedValidator() const override final;

void contactTest(ContactResultMap& collisions, const ContactRequest& request) override final;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -209,11 +209,14 @@ btTransform getLinkTransformFromCOW(const btCollisionObjectWrapper* cow);
* @brief This is used to check if a collision check is required between the provided two collision objects
* @param cow1 The first collision object
* @param cow2 The second collision object
* @param acm The contact allowed function pointer
* @param validator The contact allowed validator
* @param verbose Indicate if verbose information should be printed to the terminal
* @return True if the two collision objects should be checked for collision, otherwise false
*/
bool needsCollisionCheck(const COW& cow1, const COW& cow2, const IsContactAllowedFn& acm, bool verbose = false);
bool needsCollisionCheck(const COW& cow1,
const COW& cow2,
const std::shared_ptr<const tesseract_common::ContactAllowedValidator>& validator,
bool verbose = false);

btScalar addDiscreteSingleResult(btManifoldPoint& cp,
const btCollisionObjectWrapper* colObj0Wrap,
Expand Down
17 changes: 13 additions & 4 deletions tesseract_collision/bullet/src/bullet_cast_bvh_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "tesseract_collision/bullet/bullet_cast_bvh_manager.h"
#include <tesseract_collision/bullet/bullet_cast_bvh_manager.h>
#include <tesseract_common/contact_allowed_validator.h>

extern btScalar gDbvtMargin; // NOLINT

Expand Down Expand Up @@ -104,7 +105,7 @@ ContinuousContactManager::UPtr BulletCastBVHManager::clone() const

manager->setActiveCollisionObjects(active_);
manager->setCollisionMarginData(contact_test_data_.collision_margin_data);
manager->setIsContactAllowedFn(contact_test_data_.fn);
manager->setContactAllowedValidator(contact_test_data_.validator);

return manager;
}
Expand Down Expand Up @@ -451,8 +452,16 @@ const CollisionMarginData& BulletCastBVHManager::getCollisionMarginData() const
{
return contact_test_data_.collision_margin_data;
}
void BulletCastBVHManager::setIsContactAllowedFn(IsContactAllowedFn fn) { contact_test_data_.fn = fn; }
IsContactAllowedFn BulletCastBVHManager::getIsContactAllowedFn() const { return contact_test_data_.fn; }
void BulletCastBVHManager::setContactAllowedValidator(
std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator)
{
contact_test_data_.validator = std::move(validator);
}
std::shared_ptr<const tesseract_common::ContactAllowedValidator>
BulletCastBVHManager::getContactAllowedValidator() const
{
return contact_test_data_.validator;
}
void BulletCastBVHManager::contactTest(ContactResultMap& collisions, const ContactRequest& request)
{
contact_test_data_.res = &collisions;
Expand Down
19 changes: 14 additions & 5 deletions tesseract_collision/bullet/src/bullet_cast_simple_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "tesseract_collision/bullet/bullet_cast_simple_manager.h"
#include <tesseract_collision/bullet/bullet_cast_simple_manager.h>
#include <tesseract_common/contact_allowed_validator.h>

namespace tesseract_collision::tesseract_collision_bullet
{
Expand Down Expand Up @@ -84,7 +85,7 @@ ContinuousContactManager::UPtr BulletCastSimpleManager::clone() const

manager->setActiveCollisionObjects(active_);
manager->setCollisionMarginData(contact_test_data_.collision_margin_data);
manager->setIsContactAllowedFn(contact_test_data_.fn);
manager->setContactAllowedValidator(contact_test_data_.validator);

return manager;
}
Expand Down Expand Up @@ -364,8 +365,16 @@ const CollisionMarginData& BulletCastSimpleManager::getCollisionMarginData() con
{
return contact_test_data_.collision_margin_data;
}
void BulletCastSimpleManager::setIsContactAllowedFn(IsContactAllowedFn fn) { contact_test_data_.fn = fn; }
IsContactAllowedFn BulletCastSimpleManager::getIsContactAllowedFn() const { return contact_test_data_.fn; }
void BulletCastSimpleManager::setContactAllowedValidator(
std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator)
{
contact_test_data_.validator = std::move(validator);
}
std::shared_ptr<const tesseract_common::ContactAllowedValidator>
BulletCastSimpleManager::getContactAllowedValidator() const
{
return contact_test_data_.validator;
}
void BulletCastSimpleManager::contactTest(ContactResultMap& collisions, const ContactRequest& request)
{
contact_test_data_.res = &collisions;
Expand Down Expand Up @@ -401,7 +410,7 @@ void BulletCastSimpleManager::contactTest(ContactResultMap& collisions, const Co

if (aabb_check)
{
bool needs_collision = needsCollisionCheck(*cow1, *cow2, contact_test_data_.fn, false);
bool needs_collision = needsCollisionCheck(*cow1, *cow2, contact_test_data_.validator, false);

if (needs_collision)
{
Expand Down
15 changes: 12 additions & 3 deletions tesseract_collision/bullet/src/bullet_discrete_bvh_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
*/

#include <tesseract_collision/bullet/bullet_discrete_bvh_manager.h>
#include <tesseract_common/contact_allowed_validator.h>

extern btScalar gDbvtMargin; // NOLINT

Expand Down Expand Up @@ -100,7 +101,7 @@ DiscreteContactManager::UPtr BulletDiscreteBVHManager::clone() const

manager->setActiveCollisionObjects(active_);
manager->setCollisionMarginData(contact_test_data_.collision_margin_data);
manager->setIsContactAllowedFn(contact_test_data_.fn);
manager->setContactAllowedValidator(contact_test_data_.validator);

return manager;
}
Expand Down Expand Up @@ -272,8 +273,16 @@ const CollisionMarginData& BulletDiscreteBVHManager::getCollisionMarginData() co
{
return contact_test_data_.collision_margin_data;
}
void BulletDiscreteBVHManager::setIsContactAllowedFn(IsContactAllowedFn fn) { contact_test_data_.fn = fn; }
IsContactAllowedFn BulletDiscreteBVHManager::getIsContactAllowedFn() const { return contact_test_data_.fn; }
void BulletDiscreteBVHManager::setContactAllowedValidator(
std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator)
{
contact_test_data_.validator = std::move(validator);
}
std::shared_ptr<const tesseract_common::ContactAllowedValidator>
BulletDiscreteBVHManager::getContactAllowedValidator() const
{
return contact_test_data_.validator;
}
void BulletDiscreteBVHManager::contactTest(ContactResultMap& collisions, const ContactRequest& request)
{
contact_test_data_.res = &collisions;
Expand Down
19 changes: 14 additions & 5 deletions tesseract_collision/bullet/src/bullet_discrete_simple_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "tesseract_collision/bullet/bullet_discrete_simple_manager.h"
#include <tesseract_collision/bullet/bullet_discrete_simple_manager.h>
#include <tesseract_common/contact_allowed_validator.h>

namespace tesseract_collision::tesseract_collision_bullet
{
Expand Down Expand Up @@ -86,7 +87,7 @@ DiscreteContactManager::UPtr BulletDiscreteSimpleManager::clone() const

manager->setActiveCollisionObjects(active_);
manager->setCollisionMarginData(contact_test_data_.collision_margin_data);
manager->setIsContactAllowedFn(contact_test_data_.fn);
manager->setContactAllowedValidator(contact_test_data_.validator);

return manager;
}
Expand Down Expand Up @@ -250,8 +251,16 @@ const CollisionMarginData& BulletDiscreteSimpleManager::getCollisionMarginData()
{
return contact_test_data_.collision_margin_data;
}
void BulletDiscreteSimpleManager::setIsContactAllowedFn(IsContactAllowedFn fn) { contact_test_data_.fn = fn; }
IsContactAllowedFn BulletDiscreteSimpleManager::getIsContactAllowedFn() const { return contact_test_data_.fn; }
void BulletDiscreteSimpleManager::setContactAllowedValidator(
std::shared_ptr<const tesseract_common::ContactAllowedValidator> validator)
{
contact_test_data_.validator = std::move(validator);
}
std::shared_ptr<const tesseract_common::ContactAllowedValidator>
BulletDiscreteSimpleManager::getContactAllowedValidator() const
{
return contact_test_data_.validator;
}
void BulletDiscreteSimpleManager::contactTest(ContactResultMap& collisions, const ContactRequest& request)
{
contact_test_data_.res = &collisions;
Expand Down Expand Up @@ -287,7 +296,7 @@ void BulletDiscreteSimpleManager::contactTest(ContactResultMap& collisions, cons

if (aabb_check)
{
bool needs_collision = needsCollisionCheck(*cow1, *cow2, contact_test_data_.fn, false);
bool needs_collision = needsCollisionCheck(*cow1, *cow2, contact_test_data_.validator, false);

if (needs_collision)
{
Expand Down
13 changes: 8 additions & 5 deletions tesseract_collision/bullet/src/bullet_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -694,11 +694,14 @@ btTransform getLinkTransformFromCOW(const btCollisionObjectWrapper* cow)
return cow->getWorldTransform();
}

bool needsCollisionCheck(const COW& cow1, const COW& cow2, const IsContactAllowedFn& acm, bool verbose)
bool needsCollisionCheck(const COW& cow1,
const COW& cow2,
const std::shared_ptr<const tesseract_common::ContactAllowedValidator>& validator,
bool verbose)
{
return cow1.m_enabled && cow2.m_enabled && (cow2.m_collisionFilterGroup & cow1.m_collisionFilterMask) && // NOLINT
(cow1.m_collisionFilterGroup & cow2.m_collisionFilterMask) && // NOLINT
!isContactAllowed(cow1.getName(), cow2.getName(), acm, verbose);
!isContactAllowed(cow1.getName(), cow2.getName(), validator, verbose);
}

btScalar addDiscreteSingleResult(btManifoldPoint& cp,
Expand Down Expand Up @@ -979,7 +982,7 @@ BroadphaseContactResultCallback::BroadphaseContactResultCallback(ContactTestData
bool BroadphaseContactResultCallback::needsCollision(const CollisionObjectWrapper* cow0,
const CollisionObjectWrapper* cow1) const
{
return !collisions_.done && needsCollisionCheck(*cow0, *cow1, collisions_.fn, verbose_);
return !collisions_.done && needsCollisionCheck(*cow0, *cow1, collisions_.validator, verbose_);
}

DiscreteBroadphaseContactResultCallback::DiscreteBroadphaseContactResultCallback(ContactTestData& collisions,
Expand Down Expand Up @@ -1182,7 +1185,7 @@ bool DiscreteCollisionCollector::needsCollision(btBroadphaseProxy* proxy0) const
{
return !collisions_.done &&
needsCollisionCheck(
*cow_, *(static_cast<CollisionObjectWrapper*>(proxy0->m_clientObject)), collisions_.fn, verbose_);
*cow_, *(static_cast<CollisionObjectWrapper*>(proxy0->m_clientObject)), collisions_.validator, verbose_);
}

CastCollisionCollector::CastCollisionCollector(ContactTestData& collisions,
Expand Down Expand Up @@ -1215,7 +1218,7 @@ bool CastCollisionCollector::needsCollision(btBroadphaseProxy* proxy0) const
{
return !collisions_.done &&
needsCollisionCheck(
*cow_, *(static_cast<CollisionObjectWrapper*>(proxy0->m_clientObject)), collisions_.fn, verbose_);
*cow_, *(static_cast<CollisionObjectWrapper*>(proxy0->m_clientObject)), collisions_.validator, verbose_);
}

COW::Ptr makeCastCollisionObject(const COW::Ptr& cow)
Expand Down
3 changes: 2 additions & 1 deletion tesseract_collision/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@ add_library(
src/discrete_contact_manager.cpp
src/serialization.cpp
src/types.cpp
src/utils.cpp)
src/utils.cpp
src/contact_result_validator.cpp)
target_link_libraries(
${PROJECT_NAME}_core
PUBLIC Eigen3::Eigen
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_collision/core/types.h>
#include <tesseract_common/contact_allowed_validator.h>

namespace tesseract_collision
{
Expand All @@ -43,12 +44,13 @@ using ObjectPairKey = std::pair<std::string, std::string>;
* @todo Should this also filter out links without geometry?
* @param active_links The active link names
* @param static_links The static link names
* @param acm The is contact allowed function
* @param validator The is contact allowed validator
* @return A vector of collision object pairs
*/
std::vector<ObjectPairKey> getCollisionObjectPairs(const std::vector<std::string>& active_links,
const std::vector<std::string>& static_links,
const IsContactAllowedFn& acm = nullptr);
std::vector<ObjectPairKey>
getCollisionObjectPairs(const std::vector<std::string>& active_links,
const std::vector<std::string>& static_links,
const std::shared_ptr<const tesseract_common::ContactAllowedValidator>& validator = nullptr);

/**
* @brief This will check if a link is active provided a list. If the list is empty the link is considered active.
Expand All @@ -61,13 +63,13 @@ bool isLinkActive(const std::vector<std::string>& active, const std::string& nam
* @brief Determine if contact is allowed between two objects.
* @param name1 The name of the first object
* @param name2 The name of the second object
* @param acm The contact allowed function
* @param validator The contact allowed validator
* @param verbose If true print debug information
* @return True if contact is allowed between the two object, otherwise false.
*/
bool isContactAllowed(const std::string& name1,
const std::string& name2,
const IsContactAllowedFn& acm,
const std::shared_ptr<const tesseract_common::ContactAllowedValidator>& validator,
bool verbose = false);

/**
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
/**
* @file contact_result_validator.h
* @brief Contact result validator
*
* @author Levi Armstrong
* @date Jan 2, 2025
* @version TODO
* @bug No known bugs
*
* @copyright Copyright (c) 2025, Levi Armstrong
*
* @par License
* Software License Agreement (Apache License)
* @par
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
* http://www.apache.org/licenses/LICENSE-2.0
* @par
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef TESSERACT_COLLISION_CORE_CONTACT_RESULT_VALIDATORS_H
#define TESSERACT_COLLISION_CORE_CONTACT_RESULT_VALIDATORS_H

#include <memory>
#include <boost/serialization/access.hpp>
#include <boost/serialization/export.hpp>

namespace tesseract_collision
{
struct ContactResult;

/**
* @brief Should return true if contact results are valid, otherwise false.
*
* This is used so users may provide a callback to reject/approve collision results in various algorithms.
*/
class ContactResultValidator
{
public:
using Ptr = std::shared_ptr<ContactResultValidator>;
using ConstPtr = std::shared_ptr<const ContactResultValidator>;
using UPtr = std::unique_ptr<ContactResultValidator>;
using ConstUPtr = std::unique_ptr<const ContactResultValidator>;

virtual ~ContactResultValidator() = default;

virtual bool operator()(const ContactResult&) const = 0;

protected:
friend class boost::serialization::access;
template <class Archive>
void serialize(Archive& ar, const unsigned int version); // NOLINT
};

} // namespace tesseract_collision

BOOST_CLASS_EXPORT_KEY(tesseract_collision::ContactResultValidator)

#endif // TESSERACT_COLLISION_CORE_CONTACT_RESULT_VALIDATORS_H
Loading

0 comments on commit 11d935b

Please sign in to comment.