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

Add blacklist to BodyNodeCollisionFilter #911

Merged
merged 21 commits into from Sep 13, 2017
Merged

Conversation

jslee02
Copy link
Member

@jslee02 jslee02 commented Aug 28, 2017

This pull request enables us to enable/disable collision checking for specific pairs of body nodes by maintaining a blacklist in BodyNodeCollisionFilter. Also, ConstraintSolver::getCollisionOption() is added to enable to modify the collision filter through it as:

auto collisionOption = world->getConstraintSolver()->getCollisionOption();
auto collisionFilter = collisionOption.getCollisionFilter();
collisionFilter->addBodyNodePairToBlackList(body0, body1);

Minor changes:

  • Add CompositeCollisionFilter class to enable to use more than two collision filters by composing them in this class
  • Rename CollisionFilter::needCollision(...) to CollisionFilter::needsCollisionCheck(...)

@jslee02 jslee02 added this to the DART 6.3.0 milestone Aug 28, 2017
@codecov
Copy link

codecov bot commented Aug 28, 2017

Codecov Report

❗ No coverage uploaded for pull request base (release-6.3@6e94625). Click here to learn what that means.
The diff coverage is 60.24%.

@@              Coverage Diff               @@
##             release-6.3     #911   +/-   ##
==============================================
  Coverage               ?   50.65%           
==============================================
  Files                  ?      300           
  Lines                  ?    23482           
  Branches               ?     3029           
==============================================
  Hits                   ?    11894           
  Misses                 ?    10249           
  Partials               ?     1339
Impacted Files Coverage Δ
dart/collision/bullet/BulletCollisionDetector.cpp 58.82% <0%> (ø)
...sion/bullet/detail/BulletOverlapFilterCallback.cpp 47.36% <0%> (ø)
...lision/bullet/detail/BulletCollisionDispatcher.cpp 100% <100%> (ø)
dart/collision/fcl/FCLCollisionDetector.cpp 77.39% <100%> (ø)
dart/collision/CollisionFilter.hpp 100% <100%> (ø)
dart/collision/CollisionFilter.cpp 42% <38.7%> (ø)
dart/collision/dart/DARTCollisionDetector.cpp 66.18% <50%> (ø)
dart/constraint/ConstraintSolver.cpp 52.21% <50%> (ø)
dart/collision/detail/UnorderedPairs.hpp 77.5% <77.5%> (ø)

@mxgrey
Copy link
Member

mxgrey commented Aug 29, 2017

This is kind of a high-level thought which isn't particularly important, but I was thinking: The function name needsCollisionCheck seems a little bit disingenuous about the intent of the CollisionFilter. The boolean that gets returned isn't really indicating that a collision check is needed. Instead, a return value of true says that a collision check might be necessary, and a return value of false says that a collision check must not be performed. The CompositeCollisionFilter then checks this function on each of its filters and short-circuits when it reaches a false, as if it's performing an AND operation over all of them. However, if the function were really indicating that a collision check is needed, then CompositeCollisionFilter should be performing an OR over all of them, because if even just one of them needs the collision check, then the collision check should be performed, even if the others don't need it.

I wonder if the function name should be flipped on its head: CollisionFilter::ignoreCollision(~,~) which would return true if the collision should be skipped.

Since we're deprecating the old API and introducing a new one here anyway, this seems like it would be a good time to make this change.

@mxgrey mxgrey self-requested a review August 29, 2017 22:54
Copy link
Member

@mxgrey mxgrey left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Most of my comments are about minor tweaks that I'd be interested in hearing your thoughts on. Overall, this is a good implementation of a much-needed feature.


protected:
/// Collision filters
std::vector<CollisionFilter*> mFilters;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since we're manually enforcing uniqueness on the entries of mFilters, is there a reason we use std::vector instead of std::unordered_set? We don't appear to ever use random access for mFilters (instead, we run through it using iterators), and I'm skeptical that we'll see a noticeable improvement in performance from std::vector. I'd rather use the container that implicitly provides the properties that we want.

std::swap(bodyNodeLess, bodyNodeGreater);

// Add the pair only when it doesn't already exist
const auto resultLeft = mBlackList.find(bodyNodeLess);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a super minor nitpick, but we could use the built-in insert operator of map and set instead of all this transactional logic. The insert function won't actually insert anything into a key that already exists; it'll just return an iterator to the existing entry in the map. That would also avoid doing two lookups (one to check for existence and a second to insert the entry).

I created an example implementation here which you can feel free to merge if you like it.

const bool foundLeft = (resultLeft != mBlackList.end());
if (foundLeft)
{
auto& key = resultLeft->second;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Minor naming nitpick, but technically second is the value of an entry, and first would be the key of the entry. Maybe we can rename this to something like ... (I'm honestly struggling to think of a good name)... partners ... associates?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The canonical name here would be key -> value, but I'm guessing that's semantically pretty weak as well. Maybe just matches, pairs, or entries?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How about associatedRights?

}

//==============================================================================
bool BodyNodeCollisionFilter::needsCollisionCheck(
const collision::CollisionObject* object1,
const collision::CollisionObject* object2) const
{
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comment is really for line 171, but Github won't let me comment there:

Why do we assume that non-ShapeNodes are always checked for collisions? Is it even possible for a non-ShapeNode to provide a CollisionObject? Rather than short-circuiting if one of them is not a ShapeNode, I would expect to assert that both are, in fact, ShapeNodes.

bool areAdjacentBodies(const dynamics::BodyNode* bodyNode1,
const dynamics::BodyNode* bodyNode2) const;

/// Returns true if the BodyNode pair is in the blacklist.
bool existsBodyNodePairInBlacklist(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I totally get why the function was given this name, but I feel like it could flow better. Maybe isBodyNodePairInBlackList(~,~)? Or hasBodyNodePairInBlackList(~,~)? containsBodyNodePairInBlackList(~,~)?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I like hasBodyNodePairInBlackList(~,~)!


/// List of pairs to be excluded in the collision detection.
///
/// Each pair is stored as which the key of the std::unordered_map is not
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure this is worded correctly. It sounds like it's saying the key of the std::unordered_map is "not always greater" than the elements of its associated set when it should say that the key "is always less than or equal to" (or "is never greater").

That said, I just noticed that we're allowing BodyNodes to be paired with themselves, which I think is kind of pointless since a self-collision within a BodyNode is always true and meaningless. I think we should filter out that possibility during the adding process and make this statement "the key is always less than the elements in its associated value".

I've created a recommended rewording here.

/// std::set.
std::unordered_map<
const dynamics::BodyNode*,
std::set<const dynamics::BodyNode*>> mBlackList;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there a reason we're using std::set instead of std::unordered_set? I don't see anywhere that the order would matter.

const bool foundRight = (resultRight != key.end());
if (foundRight)
{
key.erase(bodyNodeGreater);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

One more nitpick: We don't need to check for existence before calling erase(~). If the value doesn't exist in the set, it won't erase anything. We can get rid of the if-statement and just call key.erase(bodyNodeGreater); and then if(key.empty()) mBlackList.erase(resultLeft);.

@jslee02
Copy link
Member Author

jslee02 commented Aug 30, 2017

I wonder if the function name should be flipped on its head: CollisionFilter::ignoreCollision(,) which would return true if the collision should be skipped.

I agree with you regarding the idea of changing the function name to ignoreCollision(). I actually prefer ignoresCollision as we add -s to the leading verb of the function name when it's for inquiry such as exists and has.

@jslee02
Copy link
Member Author

jslee02 commented Aug 30, 2017

I believe all the comments are addressed. @mxgrey Could you do the second round review?

@mxgrey
Copy link
Member

mxgrey commented Aug 30, 2017

ignore vs ignores is kind of an interesting point. I would read it as though the filter is giving the collision detector an instruction to "ignore the collision" between the two bodies. I would see it as a question of whether the filter is ignoring the collision (in which case, we should use ignoresCollision) or whether the collision filter is giving an instruction to the collision detector to ignore the collision (in which case, we should use ignoreCollision).

Of course there's also a third option: ignoreCollisions(~,~) which is like an instruction that all collisions between the two given bodies should be ignored.

@mxgrey
Copy link
Member

mxgrey commented Aug 30, 2017

Oh, regarding non-ShapeNodes, it just occurred to me that ShapeFrames are not ShapeNodes, but I think we want to support collision detection with ShapeFrames anyhow.

We might want to consider a ShapeFrame filter/blacklist as well. Ideally, I think we'd want to pull the blacklist functionality out of BodyNodeCollisionFilter and put it into its own templated object, like BlackListCollisionFilter<T> where T could be BodyNode or ShapeFrame. Then the BodyNodeCollisionFilter could maybe inherit BlackListCollisionFilter<BodyNode>.

@mxgrey
Copy link
Member

mxgrey commented Aug 30, 2017

After thinking about it some more, the original behavior actually made total sense for non-ShapeNodes, because the code was located within a BodyNodeCollisionFilter, which doesn't have the authority to make decisions about filtering any ShapeFrames that aren't attached to a BodyNode. So it actually should just return false for ignoresCollision, and allow other collision filters (perhaps a ShapeFrameCollisionFilter?) to decide whether the non-ShapeNode should be ignored.

Sorry for going back and forth on the matter.

Copy link
Member

@mxgrey mxgrey left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As I mentioned in a higher-level comment, I wonder if we should consider a more generic templated BlackListCollisionFilter and inherit that in BodyNodeCollisionFilter.

if (!filter)
return;

const auto result = std::find(mFilters.begin(), mFilters.end(), filter);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have two thoughts on this where the second thought makes the first through irrelevant, but I'll mention it anyway, just in case you're able to correct me:

  1. I'm not sure if std::find will take advantage of std::unordered_set's useful hashing properties. It's entirely plausible that it could (using either template specialization or function overloading), and I wouldn't be very surprised if it did, but I can't find any indication online that this is the case. So this might be performing an O(N) lookup even though our container could do a O(1) lookup. Please let me know if you're aware of any specialized optimizations that std::find performs, because I'd be very interested in knowing.

  2. Calling mFilters.insert(filter) will insert filter if it wasn't already in the set; otherwise it will do nothing. So checking to see if filter is already in the set doesn't do anything for us here.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

  1. I believe there are no specialized optimizations or that std::find performs, and also believe that there is no advantage of using std::find over std::unordered_set::find.

  2. This is just an oversight: This is a legacy code that was for when the type of mFilters was std::vector, which should be removed as std::unordered_set is used now.

@jslee02
Copy link
Member Author

jslee02 commented Aug 31, 2017

After thinking about it some more, the original behavior actually made total sense for non-ShapeNodes, because the code was located within a BodyNodeCollisionFilter, which doesn't have the authority to make decisions about filtering any ShapeFrames that aren't attached to a BodyNode. So it actually should just return false for ignoresCollision, and allow other collision filters (perhaps a ShapeFrameCollisionFilter?) to decide whether the non-ShapeNode should be ignored.

That is my original intention. I thought you meant not to allow the case that BodyNodeCollisionFilter is used for non-ShapeNode in the first place by using an assertion, but now I'm also inclined to allow the case and just return false for that case. Reverting the changes and adding a note for the future reference.

@jslee02
Copy link
Member Author

jslee02 commented Aug 31, 2017

Ideally, I think we'd want to pull the blacklist functionality out of BodyNodeCollisionFilter and put it into its own templated object, like BlackListCollisionFilter where T could be BodyNode or ShapeFrame. Then the BodyNodeCollisionFilter could maybe inherit BlackListCollisionFilter.

I like this idea. Also, I would like to generalize the functionality one step further. A collision filter should implement ignoresCollision(~) that takes const CollisionObject* as the parameter. However, in BlackListCollisionFilter<T>, it might not that be straightforward to templatize the method of associating the relationship between T and CollisionObject.

We could instead create a container that stores a set of pairs and lets us know whether a pair is in the container or not. Then BodyNodeCollisionFilter will have it as a blacklist in it instead of inheriting it.

I'm thinking of the name for the container as UnorderedPairs. A better name is always welcome.

@jslee02 jslee02 merged commit 31db2d4 into release-6.3 Sep 13, 2017
@jslee02 jslee02 deleted the feature/collision_filter branch September 13, 2017 01:33
@henryclever
Copy link

Hi,

The function auto collisionFilter = collisionOption.getCollisionFilter(); does not appear in any of the Dart source code that I can find on the master branch or others I have tried. How can I use the collision filter without this?

Thanks,
Henry C.

@jslee02
Copy link
Member Author

jslee02 commented Feb 22, 2019

Answered in #1251

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants