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

@@ -7737,6 +7737,12 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
mb->getLinkCollider(linkIndex)->setContactStiffnessAndDamping(clientCmd.m_changeDynamicsInfoArgs.m_contactStiffness, clientCmd.m_changeDynamicsInfoArgs.m_contactDamping);
}
}
if (clientCmd.m_updateFlags &CHANGE_DYNAMICS_INFO_SET_JOINT_DAMPING)
{
mb->getLink(linkIndex).m_jointDamping = clientCmd.m_changeDynamicsInfoArgs.m_jointDamping;
}
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
{
mb->getLink(linkIndex).m_mass = mass;
@@ -8057,6 +8063,7 @@ bool PhysicsServerCommandProcessor::processSendPhysicsParametersCommand(const st
BT_PROFILE("CMD_SEND_PHYSICS_SIMULATION_PARAMETERS");
if (clientCmd.m_updateFlags & SIM_PARAM_ENABLE_CONE_FRICTION)
{
if (clientCmd.m_physSimParamArgs.m_enableConeFriction)