expose PyBullet API to wakeup/put objects to sleep, enable/disable deactivation
fix wakeup -> reset deactivation clock
This commit is contained in:
@@ -2443,8 +2443,16 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetContactProcessingThreshold(b3SharedMemo
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
B3_SHARED_API int b3ChangeDynamicsInfoSetActivationState(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int activationState)
|
||||
{
|
||||
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 = -1;
|
||||
command->m_changeDynamicsInfoArgs.m_activationState = activationState;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_ACTIVATION_STATE;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info)
|
||||
|
||||
@@ -142,6 +142,7 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetContactStiffnessAndDamping(b3SharedMemo
|
||||
B3_SHARED_API int b3ChangeDynamicsInfoSetFrictionAnchor(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex, int frictionAnchor);
|
||||
B3_SHARED_API int b3ChangeDynamicsInfoSetCcdSweptSphereRadius(b3SharedMemoryCommandHandle commandHandle,int bodyUniqueId,int linkIndex, double ccdSweptSphereRadius);
|
||||
B3_SHARED_API int b3ChangeDynamicsInfoSetContactProcessingThreshold(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double contactProcessingThreshold);
|
||||
B3_SHARED_API int b3ChangeDynamicsInfoSetActivationState(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int activationState);
|
||||
|
||||
B3_SHARED_API b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyUniqueId, int parentJointIndex, int childBodyUniqueId, int childJointIndex, struct b3JointInfo* info);
|
||||
|
||||
|
||||
@@ -6599,6 +6599,26 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
|
||||
{
|
||||
btMultiBody* mb = body->m_multiBody;
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ACTIVATION_STATE)
|
||||
{
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateWakeUp)
|
||||
{
|
||||
mb->wakeUp();
|
||||
}
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateSleep)
|
||||
{
|
||||
mb->goToSleep();
|
||||
}
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateEnableSleeping)
|
||||
{
|
||||
mb->setCanSleep(true);
|
||||
}
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateDisableSleeping)
|
||||
{
|
||||
mb->setCanSleep(false);
|
||||
}
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING)
|
||||
{
|
||||
mb->setLinearDamping(clientCmd.m_changeDynamicsInfoArgs.m_linearDamping);
|
||||
@@ -6724,6 +6744,27 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
|
||||
{
|
||||
if (body && body->m_rigidBody)
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ACTIVATION_STATE)
|
||||
{
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateEnableSleeping)
|
||||
{
|
||||
body->m_rigidBody->forceActivationState(ACTIVE_TAG);
|
||||
}
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateDisableSleeping)
|
||||
{
|
||||
body->m_rigidBody->forceActivationState(DISABLE_DEACTIVATION);
|
||||
}
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateWakeUp)
|
||||
{
|
||||
body->m_rigidBody->forceActivationState(ACTIVE_TAG);
|
||||
}
|
||||
if (clientCmd.m_changeDynamicsInfoArgs.m_activationState&eActivationStateSleep)
|
||||
{
|
||||
body->m_rigidBody->forceActivationState(ISLAND_SLEEPING);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING)
|
||||
{
|
||||
btScalar angDamping = body->m_rigidBody->getAngularDamping();
|
||||
|
||||
@@ -166,6 +166,7 @@ enum EnumChangeDynamicsInfoFlags
|
||||
CHANGE_DYNAMICS_INFO_SET_LOCAL_INERTIA_DIAGONAL = 1024,
|
||||
CHANGE_DYNAMICS_INFO_SET_CCD_SWEPT_SPHERE_RADIUS = 2048,
|
||||
CHANGE_DYNAMICS_INFO_SET_CONTACT_PROCESSING_THRESHOLD = 4096,
|
||||
CHANGE_DYNAMICS_INFO_SET_ACTIVATION_STATE = 8192,
|
||||
};
|
||||
|
||||
struct ChangeDynamicsInfoArgs
|
||||
@@ -186,6 +187,7 @@ struct ChangeDynamicsInfoArgs
|
||||
int m_frictionAnchor;
|
||||
double m_ccdSweptSphereRadius;
|
||||
double m_contactProcessingThreshold;
|
||||
int m_activationState;
|
||||
};
|
||||
|
||||
struct GetDynamicsInfoArgs
|
||||
|
||||
@@ -314,6 +314,15 @@ struct b3BodyInfo
|
||||
char m_bodyName[1024]; // for btRigidBody, it does not have a base, but can still have a body name from urdf
|
||||
};
|
||||
|
||||
|
||||
enum DynamicsActivationState
|
||||
{
|
||||
eActivationStateEnableSleeping = 1,
|
||||
eActivationStateDisableSleeping = 2,
|
||||
eActivationStateWakeUp = 4,
|
||||
eActivationStateSleep = 8,
|
||||
};
|
||||
|
||||
struct b3DynamicsInfo
|
||||
{
|
||||
double m_mass;
|
||||
|
||||
Reference in New Issue
Block a user