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

bullet-featherstone: Fix bounding box for collisions with pose offset #647

Merged
merged 3 commits into from
Jun 5, 2024

Conversation

iche033
Copy link
Contributor

@iche033 iche033 commented Jun 3, 2024

🦟 Bug fix

hide whitespace changes for better diff:
https://github.com/gazebosim/gz-physics/pull/647/files?w=1

Summary

Currently if a collision has a pose offset, the bullet-featherstone plugin return an incorrect axis aligned bounding box for the link containing the collision. This is found to be caused by incorrect frame data pose computed for collisions - It currently ignores the collision pose offset.

This PR makes a few changes to KinematicsFeatures::FrameDataRelativeToWorld in bullet-featherstone plugin:

  • fixed getting collision pose relative to world
  • fixed getting model pose relative to world
  • minor refactoring

The link_features's bounding box test was previously skipped for bullet-featherstone plugin. This PR enables this test for bullet-featherstone by requiring only a minimal set of features needed to run the test.

Checklist

  • Signed all commits for DCO
  • Added tests
  • Updated documentation (as needed)
  • Updated migration guide (as needed)
  • Consider updating Python bindings (if the library has them)
  • codecheck passed (See contributing)
  • All tests passed (See test coverage)
  • While waiting for a review on your PR, please help review another open pull request to support the maintainers

Note to maintainers: Remember to use Squash-Merge and edit the commit message to match the pull request summary while retaining Signed-off-by messages.

@github-actions github-actions bot added the 🎵 harmonic Gazebo Harmonic label Jun 3, 2024
@iche033 iche033 added the Bullet Bullet engine label Jun 3, 2024
Copy link

codecov bot commented Jun 3, 2024

Codecov Report

Attention: Patch coverage is 92.30769% with 3 lines in your changes missing coverage. Please review.

Project coverage is 79.06%. Comparing base (92e02c3) to head (4f35c1e).
Report is 17 commits behind head on gz-physics7.

Current head 4f35c1e differs from pull request most recent head 84054fa

Please upload reports for the commit 84054fa to get more accurate results.

Files Patch % Lines
bullet-featherstone/src/KinematicsFeatures.cc 92.30% 3 Missing ⚠️
Additional details and impacted files
@@               Coverage Diff               @@
##           gz-physics7     #647      +/-   ##
===============================================
+ Coverage        78.32%   79.06%   +0.74%     
===============================================
  Files              140      140              
  Lines             8069     8235     +166     
===============================================
+ Hits              6320     6511     +191     
+ Misses            1749     1724      -25     

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

Copy link
Contributor

@azeey azeey left a comment

Choose a reason for hiding this comment

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

Mostly looks good. I just have one question.

{
data.pose = convert(model->body->getBaseWorldTransform())
* model->baseInertiaToLinkFrame;
data.pose = convert(model->body->getBaseWorldTransform());
Copy link
Contributor

Choose a reason for hiding this comment

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

Don't we have to account for

  • The offset from the model to the base link, i.e, the links pose in SDF? Do we have a test that covers this?
  • The offset of the link frame to the center of mass? I thought that's what model->baseInertiaToLinkFrame was there for .

Copy link
Contributor Author

@iche033 iche033 Jun 4, 2024

Choose a reason for hiding this comment

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

This line computes the pose for the model. The next 2 lines takes into account the pose of the link (and inertia offset if any) which uses model->baseInertiaToLinkFrame. I think that's correct? I added a test in 5c6ec0f that checks the frame data for a link and a collision, both of which have a pose offset.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

expanded test to cover both base and non-base links. 84054fa

Copy link
Contributor

Choose a reason for hiding this comment

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

It looks like this test is not testing model frame semantics at all. Fortunately, we currently don't use it in gz-sim, but it would be good to fix (not in this PR). I've added a failing test in the azeey/kinematic_feature_failing_test branch. Evidently, dartsim fails the test as well.

Copy link
Contributor

@azeey azeey left a comment

Choose a reason for hiding this comment

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

The fix for Collision looks good to me. I think there's still an issue with model FrameData calculation, but I think it would be best to address in a separate PR.

{
data.pose = convert(model->body->getBaseWorldTransform())
* model->baseInertiaToLinkFrame;
data.pose = convert(model->body->getBaseWorldTransform());
Copy link
Contributor

Choose a reason for hiding this comment

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

It looks like this test is not testing model frame semantics at all. Fortunately, we currently don't use it in gz-sim, but it would be good to fix (not in this PR). I've added a failing test in the azeey/kinematic_feature_failing_test branch. Evidently, dartsim fails the test as well.

@iche033
Copy link
Contributor Author

iche033 commented Jun 5, 2024

Thanks for adding the test. I'm tracking all frame data issues in #648

@azeey azeey merged commit 1d9ede3 into gz-physics7 Jun 5, 2024
7 checks passed
@azeey azeey deleted the bullet_col_bbox branch June 5, 2024 14:53
@iche033
Copy link
Contributor Author

iche033 commented Jun 5, 2024

I think there's still an issue with model FrameData calculation, but I think it would be best to address in a separate PR.

Follow-up PR: #649

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Bullet Bullet engine 🎵 harmonic Gazebo Harmonic
Projects
Archived in project
Development

Successfully merging this pull request may close these issues.

2 participants