gz-physics
gz-physics copied to clipboard
bullet-featherstone: Add Kinematic feature
🎉 New feature
Summary
Note: bullet version >=3.07 is need for this feature. On Jammy, the version is 3.06 so you'll need to build bullet from source. Noble should come with 3.24
Initial support for kinematic mode in bullet-featherstone implementation.
- Adds a new Kinematic feature
- Looking for feedback - In the physics plugin, I added the implementation in a new KinematicFeatures class. However, there is already a class with very similar name, KinematicsFeatures (note the extra s) for handling frame semantics. This may create confusion in the future so I'm open to renaming the feature.
- Reads the
<kinematic>
SDF value sets a link to kinematic iftrue
.- sdformat support added in https://github.com/gazebosim/sdformat/pull/1390
Not supported yet - setting velocity to a kinematic link or to a joint connecting kinematic links.
Test it
Added tests to make sure we can make base and non-base links kinematic.
You can also test with gz-sim.
Example: the base
and upper_link
links are set to kinematic in the pendulum_links.sdf.
patch
diff --git a/examples/worlds/pendulum_links.sdf b/examples/worlds/pendulum_links.sdf
index 5eecd1893..bd5ec53d5 100644
--- a/examples/worlds/pendulum_links.sdf
+++ b/examples/worlds/pendulum_links.sdf
@@ -71,6 +71,7 @@
<model name="double_pendulum_with_base">
<link name="base">
+ <kinematic>true</kinematic>
<inertial>
<pose>-0.188749 0 0.75813399999999997 -0.13567899999999999 0 1.5708</pose>
<mass>256.42500000000001</mass>
@@ -130,6 +131,7 @@
</link>
<!-- upper link, length 1, IC -90 degrees -->
<link name="upper_link">
+ <kinematic>true</kinematic>
<pose>0 0 2.1 -1.5708 0 0</pose>
<self_collide>0</self_collide>
<inertial>
Launch the world with bullet-featherstone plugin:
gz sim -v 4 <path_to_pendulum_links.sdf> --physics-engine gz-physics-bullet-featherstone-plugin
Checklist
- [ ] Signed all commits for DCO
- [ ] Added tests
- [ ] Added example and/or tutorial
- [ ] 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.
Codecov Report
Attention: Patch coverage is 0%
with 4 lines
in your changes are missing coverage. Please review.
Project coverage is 78.36%. Comparing base (
492b124
) to head (d175730
). Report is 16 commits behind head on main.
:exclamation: Current head d175730 differs from pull request most recent head 894645d. Consider uploading reports for the commit 894645d to get more accurate results
Files | Patch % | Lines |
---|---|---|
include/gz/physics/detail/Kinematic.hh | 0.00% | 4 Missing :warning: |
Additional details and impacted files
@@ Coverage Diff @@
## main #618 +/- ##
==========================================
+ Coverage 78.32% 78.36% +0.04%
==========================================
Files 140 141 +1
Lines 8069 8136 +67
==========================================
+ Hits 6320 6376 +56
- Misses 1749 1760 +11
:umbrella: View full report in Codecov by Sentry.
:loudspeaker: Have feedback on the report? Share it here.
I think we need more documentation on what it means for a Link
to be Kinematic
, including the documenation for the SDFormat //link/kinematic
tag:
- http://sdformat.org/spec?ver=1.11&elem=link#link_kinematic
I'm currently looking at the documentation for ODE and bullet for inspiration:
- https://ode.org/wiki/index.php/Manual#Kinematic_State
- page 19: https://github.com/bulletphysics/bullet3/blob/master/docs/Bullet_User_Manual.pdf
I think we need more documentation on what it means for a
Link
to beKinematic
, including the documenation for the SDFormat//link/kinematic
tag:
- http://sdformat.org/spec?ver=1.11&elem=link#link_kinematic
I'm currently looking at the documentation for ODE and bullet for inspiration:
- https://ode.org/wiki/index.php/Manual#Kinematic_State
- page 19: https://github.com/bulletphysics/bullet3/blob/master/docs/Bullet_User_Manual.pdf
also for dart: https://github.com/dartsim/dart/blob/main/dart/dynamics/Joint.hpp#L178-L187
I think we need more documentation on what it means for a
Link
to beKinematic
, including the documenation for the SDFormat//link/kinematic
tag:
I expanded the SDF description in https://github.com/gazebosim/sdformat/pull/1462 and updated the Link SetKinematic
API doc in c2e2f40