Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve collision detection API for binary check #694

Merged
merged 20 commits into from
May 11, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
ef60ea4
Add convenient functions for binary collision checks
jslee02 Apr 24, 2016
2455923
Merge remote-tracking branch 'origin/master' into js/collide_without_…
jslee02 Apr 26, 2016
9222a15
Merge remote-tracking branch 'origin/master' into js/collide_without_…
jslee02 May 4, 2016
f9d4b51
Change CollisionResult parameter to optional pointer rather than refe…
jslee02 May 6, 2016
c86bbff
Change CollisionResult parameter to optional pointer of DARTCollision…
jslee02 May 6, 2016
045fa7c
Change World::checkCollision(~) to take collision option and result p…
jslee02 May 6, 2016
62fb94b
Check if result is nullptr in DARTCollisionDetector::collide
jslee02 May 7, 2016
b6b3183
Change CollisionResult parameter to optional pointer of BulletCollisi…
jslee02 May 8, 2016
4be219e
Update use of collide functions
jslee02 May 8, 2016
08b5dc3
Remove Option::binaryCheck. Set Option::maxNumContacts == 1u instead.
jslee02 May 8, 2016
93ab34b
Add test for collision filter -- failing with BulletCollisionDetector
jslee02 May 8, 2016
8cf65f2
Merge remote-tracking branch 'origin/master' into js/collide_without_…
jslee02 May 8, 2016
7299ba7
Workaround to enable collision filter for BulletCollisionDetector
jslee02 May 8, 2016
5bfe8d4
Add test of group-group collision checking
jslee02 May 8, 2016
a8f094a
Merge remote-tracking branch 'origin/master' into js/collide_without_…
jslee02 May 9, 2016
9a95a32
Merge remote-tracking branch 'origin/master' into js/collide_without_…
jslee02 May 9, 2016
6a318a7
Suppress warning by not using deprecated API in testCollision.cpp
jslee02 May 9, 2016
584d942
Add a warning to BulletCollisionDetector::collide(group1, group2)
jslee02 May 10, 2016
fe08fec
Fix segfault of BulletCollisionDetector on Mac
jslee02 May 10, 2016
863151c
Update minor code style in ConstraintSolver::removeSkeleton(~)
jslee02 May 10, 2016
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 12 additions & 5 deletions dart/collision/CollisionDetector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,15 +98,22 @@ class CollisionDetector : public std::enable_shared_from_this<CollisionDetector>
std::shared_ptr<CollisionGroup> createCollisionGroupAsSharedPtr(
const Args&... args);

/// Perform collision detection for group.
/// Perform collision check for a single group. If nullptr is passed to
/// result, then the this returns only simple information whether there is a
/// collision of not.
virtual bool collide(
CollisionGroup* group,
const CollisionOption& option, CollisionResult& result) = 0;
const CollisionOption& option = CollisionOption(false, 1u, nullptr),
CollisionResult* result = nullptr) = 0;

/// Perform collision detection for group1-group2.
/// Perform collision check for two groups. If nullptr is passed to
/// result, then the this returns only simple information whether there is a
/// collision of not.
virtual bool collide(
CollisionGroup* group1, CollisionGroup* group2,
const CollisionOption& option, CollisionResult& result) = 0;
CollisionGroup* group1,
CollisionGroup* group2,
const CollisionOption& option = CollisionOption(false, 1u, nullptr),
CollisionResult* result = nullptr) = 0;

protected:

Expand Down
7 changes: 5 additions & 2 deletions dart/collision/CollisionGroup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,14 +166,17 @@ const dynamics::ShapeFrame* CollisionGroup::getShapeFrame(
}

//==============================================================================
bool CollisionGroup::collide(const CollisionOption& option, CollisionResult& result)
bool CollisionGroup::collide(
const CollisionOption& option, CollisionResult* result)
{
return mCollisionDetector->collide(this, option, result);
}

//==============================================================================
bool CollisionGroup::collide(
CollisionGroup* other, const CollisionOption& option, CollisionResult& result)
CollisionGroup* other,
const CollisionOption& option,
CollisionResult* result)
{
return mCollisionDetector->collide(this, other, option, result);
}
Expand Down
14 changes: 9 additions & 5 deletions dart/collision/CollisionGroup.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,15 +171,19 @@ class CollisionGroup
/// Get the ShapeFrame corresponding to the given index
const dynamics::ShapeFrame* getShapeFrame(std::size_t index) const;

/// Perform collision detection within this CollisionGroup.
bool collide(const CollisionOption& option, CollisionResult& result);
/// Perform collision check within this CollisionGroup.
bool collide(
const CollisionOption& option = CollisionOption(false, 1u, nullptr),
CollisionResult* result = nullptr);

/// Perform collision detection with other CollisionGroup.
/// Perform collision check with other CollisionGroup.
///
/// Return false if the engine type of the other CollisionGroup is different
/// from this CollisionObject engine.
bool collide(CollisionGroup* group,
const CollisionOption& option, CollisionResult& result);
bool collide(
CollisionGroup* group,
const CollisionOption& option = CollisionOption(false, 1u, nullptr),
CollisionResult* result = nullptr);

protected:

Expand Down
2 changes: 0 additions & 2 deletions dart/collision/Option.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,9 @@ namespace collision {
//==============================================================================
CollisionOption::CollisionOption(
bool enableContact,
bool binaryCheck,
std::size_t maxNumContacts,
const std::shared_ptr<CollisionFilter>& collisionFilter)
: enableContact(enableContact),
binaryCheck(binaryCheck),
maxNumContacts(maxNumContacts),
collisionFilter(collisionFilter)
{
Expand Down
25 changes: 13 additions & 12 deletions dart/collision/Option.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,26 +47,27 @@ class CollisionFilter;

struct CollisionOption
{
/// Flag whether compute contact information such as point, normal, and
/// penetration depth. If this flag is set to false, the Engine returns only
/// simple information whether there is a collision of not.
bool enableContact;

/// If true, the collision checking will terminate as soon as the first
/// contact is found.
bool binaryCheck;
/// Flag whether the collision detector computes contact information (contact
/// point, normal, and penetration depth). If it is set to false, only the
/// result of that which pairs are colliding will be stored in the
/// CollisionResult without the contact information.
bool enableContact;

/// Maximum number of contacts to detect
/// Maximum number of contacts to detect. Once the contacts are found up to
/// this number, the collision checking will terminate at that moment. Set
/// this to 1 for binary check.
std::size_t maxNumContacts;

/// CollisionFilter
std::shared_ptr<CollisionFilter> collisionFilter;

/// Constructor
CollisionOption(bool enableContact = true,
bool binaryCheck = false,
std::size_t maxNumContacts = 100,
const std::shared_ptr<CollisionFilter>& collisionFilter = nullptr);
CollisionOption(
bool enableContact = true,
std::size_t maxNumContacts = 1000u,
const std::shared_ptr<CollisionFilter>& collisionFilter = nullptr);

};

} // namespace collision
Expand Down
Loading