-
Notifications
You must be signed in to change notification settings - Fork 41
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
Minor optimization for picking contact points in dartsim's ODE collision detector #584
Merged
Merged
Changes from 20 commits
Commits
Show all changes
24 commits
Select commit
Hold shift + click to select a range
e01a252
add max contacts feature
iche033 72ad146
add support for max contacts in dart's ode collision detector
iche033 e0d0cb1
add test
iche033 fa9830f
revert world changes, add tests
iche033 9cc40ae
cleanup
iche033 1016ec0
style, add includes
iche033 c428a3c
fix comments
iche033 52af0a2
Contact point selection
iche033 a2bcbf0
add include
iche033 9da1af3
fix edge case
iche033 98b5e61
MaxContacts -> CollisionPairMaxTotalContacts
iche033 af1655c
line wrap
iche033 da72c73
Merge branch 'max_contacts_ode' into max_contacts_ode_2
iche033 e4e51e1
copyright year
iche033 b140329
CollisionPairMaxTotalContacts -> CollisionPairMaxContacts
iche033 2e97b18
Merge branch 'max_contacts_ode' into max_contacts_ode_2
iche033 89d6347
fix doc
iche033 20ccc51
add test for selecting contact with max depth
iche033 6e57e47
Merge branch 'max_contacts_ode' into max_contacts_ode_2
iche033 b9e3fa6
remove comments
iche033 115b541
reset pose between steps
iche033 628a9b6
merge from gz-physics6 and resolve conflicts
iche033 b5592a4
Merge branch 'gz-physics6' into max_contacts_ode_2
iche033 93ec7a1
Merge branch 'gz-physics6' into max_contacts_ode_2
iche033 File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,137 @@ | ||
/* | ||
* Copyright (C) 2024 Open Source Robotics Foundation | ||
* | ||
* 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 | ||
* | ||
* 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. | ||
* | ||
*/ | ||
|
||
#include <memory> | ||
#include <unordered_map> | ||
#include <utility> | ||
|
||
#include <dart/collision/CollisionObject.hpp> | ||
|
||
#include "GzOdeCollisionDetector.hh" | ||
|
||
using namespace dart; | ||
using namespace collision; | ||
|
||
///////////////////////////////////////////////// | ||
GzOdeCollisionDetector::GzOdeCollisionDetector() | ||
: OdeCollisionDetector() | ||
{ | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
GzOdeCollisionDetector::Registrar<GzOdeCollisionDetector> | ||
GzOdeCollisionDetector::mRegistrar{ | ||
GzOdeCollisionDetector::getStaticType(), | ||
[]() -> std::shared_ptr<GzOdeCollisionDetector> { | ||
return GzOdeCollisionDetector::create(); | ||
}}; | ||
|
||
///////////////////////////////////////////////// | ||
std::shared_ptr<GzOdeCollisionDetector> GzOdeCollisionDetector::create() | ||
{ | ||
return std::shared_ptr<GzOdeCollisionDetector>(new GzOdeCollisionDetector()); | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
bool GzOdeCollisionDetector::collide( | ||
CollisionGroup *_group, | ||
const CollisionOption &_option, | ||
CollisionResult *_result) | ||
{ | ||
bool ret = OdeCollisionDetector::collide(_group, _option, _result); | ||
this->LimitCollisionPairMaxContacts(_result); | ||
return ret; | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
bool GzOdeCollisionDetector::collide( | ||
CollisionGroup *_group1, | ||
CollisionGroup *_group2, | ||
const CollisionOption &_option, | ||
CollisionResult *_result) | ||
{ | ||
bool ret = OdeCollisionDetector::collide(_group1, _group2, _option, _result); | ||
this->LimitCollisionPairMaxContacts(_result); | ||
return ret; | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
void GzOdeCollisionDetector::SetCollisionPairMaxContacts( | ||
std::size_t _maxContacts) | ||
{ | ||
this->maxCollisionPairContacts = _maxContacts; | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
std::size_t GzOdeCollisionDetector::GetCollisionPairMaxContacts() const | ||
{ | ||
return this->maxCollisionPairContacts; | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
void GzOdeCollisionDetector::LimitCollisionPairMaxContacts( | ||
CollisionResult *_result) | ||
{ | ||
if (this->maxCollisionPairContacts == | ||
std::numeric_limits<std::size_t>::max()) | ||
return; | ||
|
||
auto allContacts = _result->getContacts(); | ||
_result->clear(); | ||
|
||
|
||
if (this->maxCollisionPairContacts == 0u) | ||
return; | ||
|
||
// A map of collision pairs and their contact info | ||
// Contact info is stored in std::pair. The elements are: | ||
// <contact count, index of last contact point (in _result)> | ||
std::unordered_map<dart::collision::CollisionObject *, | ||
std::unordered_map<dart::collision::CollisionObject *, | ||
std::pair<std::size_t, std::size_t>>> | ||
contactMap; | ||
|
||
for (auto &contact : allContacts) | ||
{ | ||
auto &[count, lastContactIdx] = | ||
contactMap[contact.collisionObject1][contact.collisionObject2]; | ||
count++; | ||
auto &[otherCount, otherLastContactIdx] = | ||
contactMap[contact.collisionObject2][contact.collisionObject1]; | ||
|
||
std::size_t total = count + otherCount; | ||
if (total <= this->maxCollisionPairContacts) | ||
{ | ||
if (total == this->maxCollisionPairContacts) | ||
{ | ||
lastContactIdx = _result->getNumContacts(); | ||
otherLastContactIdx = lastContactIdx; | ||
} | ||
_result->addContact(contact); | ||
} | ||
else | ||
{ | ||
// If too many contacts were generated, replace the last contact point | ||
// of the collision pair with one that has a larger penetration depth | ||
auto &c = _result->getContact(lastContactIdx); | ||
if (contact.penetrationDepth > c.penetrationDepth) | ||
{ | ||
c = contact; | ||
} | ||
} | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,73 @@ | ||
/* | ||
* Copyright (C) 2024 Open Source Robotics Foundation | ||
* | ||
* 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 | ||
* | ||
* 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. | ||
* | ||
*/ | ||
|
||
#include <limits> | ||
#include <memory> | ||
|
||
#include <dart/collision/ode/OdeCollisionDetector.hpp> | ||
|
||
namespace dart { | ||
namespace collision { | ||
|
||
class GzOdeCollisionDetector : public dart::collision::OdeCollisionDetector | ||
{ | ||
// Documentation inherited | ||
public: bool collide( | ||
CollisionGroup* group, | ||
const CollisionOption& option = CollisionOption(false, 1u, nullptr), | ||
CollisionResult* result = nullptr) override; | ||
|
||
// Documentation inherited | ||
public: bool collide( | ||
CollisionGroup* group1, | ||
CollisionGroup* group2, | ||
const CollisionOption& option = CollisionOption(false, 1u, nullptr), | ||
CollisionResult* result = nullptr) override; | ||
|
||
/// \brief Set the maximum number of contacts between a pair of collision | ||
/// objects | ||
/// \param[in] _maxContacts Maximum number of contacts between a pair of | ||
/// collision objects. | ||
public: void SetCollisionPairMaxContacts(std::size_t _maxContacts); | ||
|
||
/// \brief Get the maximum number of contacts between a pair of collision | ||
/// objects | ||
/// \return Maximum number of contacts between a pair of collision objects. | ||
public: std::size_t GetCollisionPairMaxContacts() const; | ||
|
||
|
||
/// \brief Create the GzOdeCollisionDetector | ||
public: static std::shared_ptr<GzOdeCollisionDetector> create(); | ||
|
||
/// Constructor | ||
protected: GzOdeCollisionDetector(); | ||
|
||
/// \brief Limit max number of contacts between a pair of collision objects. | ||
/// The function modifies the contacts vector inside the CollisionResult | ||
/// object to cap the number of contacts for each collision pair based on the | ||
/// maxCollisionPairContacts value | ||
private: void LimitCollisionPairMaxContacts(CollisionResult *_result); | ||
|
||
/// \brief Maximum number of contacts between a pair of collision objects. | ||
private: std::size_t maxCollisionPairContacts = | ||
std::numeric_limits<std::size_t>::max(); | ||
|
||
private: static Registrar<GzOdeCollisionDetector> mRegistrar; | ||
}; | ||
|
||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
this does match what gazebo-classic was doing, so I think it's a reasonable place to start, but reading this code raises questions for me about what should be done.
One approach could be to sort contacts by penetration depth and choose the points with the maximum depth values, but then you could still have to choose between points if their depth values were identical. Then again, the computational cost must also be considered
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
yeah I think that's a good approach and see if how that much extra sorting logic costs. We can consider this as a follow up improvement?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
👍