expose a maximum velocity due to the joint motor in position control.

see also pybullet/examples/motorMaxVelocity.py
this fixes issue 1444
This commit is contained in:
erwincoumans
2017-11-21 17:05:28 -08:00
parent 3f60be59ad
commit ab843b26f0
6 changed files with 42 additions and 4 deletions

View File

@@ -4531,6 +4531,10 @@ bool PhysicsServerCommandProcessor::processSendDesiredStateCommand(const struct
if (motor)
{
if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex]&SIM_DESIRED_STATE_HAS_RHS_CLAMP)!=0)
{
motor->setRhsClamp(clientCmd.m_sendDesiredStateCommandArgument.m_rhsClamp[velIndex]);
}
bool hasDesiredPosOrVel = false;
btScalar kp = 0.f;