perform IK in local body-fixed frame

For now, Jacobian, mass matrix and inverse dynamics return results in local coordinates of the tree.
This commit is contained in:
Erwin Coumans
2017-10-24 21:06:44 -07:00
parent 1998a62785
commit 41a1362bc5
3 changed files with 45 additions and 8 deletions

View File

@@ -27,7 +27,9 @@ int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const
} else {
link.joint_type = FLOATING;
}
btTransform transform(btmb->getBaseWorldTransform());
btTransform transform=(btmb->getBaseWorldTransform());
//compute inverse dynamics in body-fixed frame
transform.setIdentity();
link.parent_r_parent_body_ref(0) = transform.getOrigin()[0];
link.parent_r_parent_body_ref(1) = transform.getOrigin()[1];