PyBullet.changeDynamics: expose jointDamping

PyBullet: Implement a few more APIs of PhysX backend, resetJointState and setJointMotorControl2
allow useMaximalCoordinate=True for PhysX loadURDF (only for single rigid bodies, articulations require reduced coordinates at the moment)
This commit is contained in:
erwincoumans
2019-02-04 21:06:43 -08:00
parent 2eace2f715
commit 42369aa47d
10 changed files with 1019 additions and 253 deletions

View File

@@ -2831,6 +2831,18 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetAngularDamping(b3SharedMemoryCommandHan
return 0;
}
B3_SHARED_API int b3ChangeDynamicsInfoSetJointDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double jointDamping)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO);
command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_changeDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_changeDynamicsInfoArgs.m_jointDamping = jointDamping;
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_JOINT_DAMPING;
return 0;
}
B3_SHARED_API int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double contactStiffness, double contactDamping)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;