fix the pybullet.changeDynamics linear/angular damping

expose pybullet.getConstraintState
This commit is contained in:
Erwin Coumans
2017-10-18 19:15:35 -07:00
parent 618deae3e4
commit c178c101a8
8 changed files with 154 additions and 16 deletions

View File

@@ -601,6 +601,10 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
break;
}
case CMD_USER_CONSTRAINT_REQUEST_STATE_COMPLETED:
{
break;
}
case CMD_USER_CONSTRAINT_INFO_COMPLETED:
{
B3_PROFILE("CMD_USER_CONSTRAINT_INFO_COMPLETED");