expose pybullet changeDynamics(spinningFriction=..., rollingFriction=..., restitution=...)
Bullet C-API b3ChangeDynamicsInfoSetSpinningFriction/RollingFriction/Resitution b3PhysicsParamSetRestitutionVelocityThreshold, / pybullet.setPhysicsEngineParameter restitutionVelocityThreshold: if the velocity is below this threshhold, the restitution is zero (this prevents energy buildup at near-resting state) pybullet restitution.py example.
This commit is contained in:
@@ -392,6 +392,18 @@ int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle
|
||||
|
||||
}
|
||||
|
||||
int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
|
||||
|
||||
command->m_physSimParamArgs.m_restitutionVelocityThreshold = restitutionVelocityThreshold;
|
||||
command->m_updateFlags |= SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD ;
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
@@ -1297,6 +1309,42 @@ int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHa
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction)
|
||||
{
|
||||
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_spinningFriction = friction;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION;
|
||||
return 0;
|
||||
|
||||
}
|
||||
int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction)
|
||||
{
|
||||
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_rollingFriction = friction;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION;
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution)
|
||||
{
|
||||
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_restitution = restitution;
|
||||
command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_RESTITUTION;
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient* ) physClient;
|
||||
|
||||
@@ -84,7 +84,12 @@ int b3GetDynamicsInfo(b3SharedMemoryStatusHandle statusHandle, struct b3Dynamics
|
||||
b3SharedMemoryCommandHandle b3InitChangeDynamicsInfo(b3PhysicsClientHandle physClient);
|
||||
int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass);
|
||||
int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction);
|
||||
|
||||
int b3ChangeDynamicsInfoSetSpinningFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction);
|
||||
int b3ChangeDynamicsInfoSetRollingFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double friction);
|
||||
int b3ChangeDynamicsInfoSetRestitution(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double restitution);
|
||||
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info);
|
||||
|
||||
///return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id
|
||||
@@ -222,6 +227,9 @@ int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandl
|
||||
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
|
||||
int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms);
|
||||
int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching);
|
||||
int b3PhysicsParamSetRestitutionVelocityThreshold(b3SharedMemoryCommandHandle commandHandle, double restitutionVelocityThreshold);
|
||||
|
||||
|
||||
|
||||
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
|
||||
//Use at own risk: magic things may or my not happen when calling this API
|
||||
|
||||
@@ -3915,52 +3915,122 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
BT_PROFILE("CMD_CHANGE_DYNAMICS_INFO");
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
|
||||
{
|
||||
int bodyUniqueId = clientCmd.m_changeDynamicsInfoArgs.m_bodyUniqueId;
|
||||
int linkIndex = clientCmd.m_changeDynamicsInfoArgs.m_linkIndex;
|
||||
double mass = clientCmd.m_changeDynamicsInfoArgs.m_mass;
|
||||
btAssert(bodyUniqueId >= 0);
|
||||
btAssert(linkIndex >= -1);
|
||||
int bodyUniqueId = clientCmd.m_changeDynamicsInfoArgs.m_bodyUniqueId;
|
||||
int linkIndex = clientCmd.m_changeDynamicsInfoArgs.m_linkIndex;
|
||||
double mass = clientCmd.m_changeDynamicsInfoArgs.m_mass;
|
||||
double lateralFriction = clientCmd.m_changeDynamicsInfoArgs.m_lateralFriction;
|
||||
double spinningFriction = clientCmd.m_changeDynamicsInfoArgs.m_spinningFriction;
|
||||
double rollingFriction = clientCmd.m_changeDynamicsInfoArgs.m_rollingFriction;
|
||||
double restitution = clientCmd.m_changeDynamicsInfoArgs.m_restitution;
|
||||
btAssert(bodyUniqueId >= 0);
|
||||
btAssert(linkIndex >= -1);
|
||||
|
||||
InteralBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId);
|
||||
if (body && body->m_multiBody)
|
||||
InteralBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId);
|
||||
|
||||
if (body && body->m_multiBody)
|
||||
{
|
||||
btMultiBody* mb = body->m_multiBody;
|
||||
if (linkIndex == -1)
|
||||
{
|
||||
btMultiBody* mb = body->m_multiBody;
|
||||
if (linkIndex == -1)
|
||||
if (mb->getBaseCollider())
|
||||
{
|
||||
mb->setBaseMass(mass);
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_RESTITUTION)
|
||||
{
|
||||
mb->getBaseCollider()->setRestitution(restitution);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
mb->getBaseCollider()->setFriction(lateralFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION)
|
||||
{
|
||||
mb->getBaseCollider()->setSpinningFriction(spinningFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION)
|
||||
{
|
||||
mb->getBaseCollider()->setRollingFriction(rollingFriction);
|
||||
}
|
||||
}
|
||||
else
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
|
||||
{
|
||||
mb->setBaseMass(mass);
|
||||
if (mb->getBaseCollider() && mb->getBaseCollider()->getCollisionShape())
|
||||
{
|
||||
btVector3 localInertia;
|
||||
mb->getBaseCollider()->getCollisionShape()->calculateLocalInertia(mass,localInertia);
|
||||
mb->setBaseInertia(localInertia);
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (mb->getLinkCollider(linkIndex))
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_RESTITUTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setRestitution(restitution);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setSpinningFriction(spinningFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setRollingFriction(rollingFriction);
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setFriction(lateralFriction);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
|
||||
{
|
||||
mb->getLink(linkIndex).m_mass = mass;
|
||||
if (mb->getLinkCollider(linkIndex) && mb->getLinkCollider(linkIndex)->getCollisionShape())
|
||||
{
|
||||
btVector3 localInertia;
|
||||
mb->getLinkCollider(linkIndex)->getCollisionShape()->calculateLocalInertia(mass,localInertia);
|
||||
mb->getLink(linkIndex).m_inertiaLocal = localInertia;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
} else
|
||||
{
|
||||
if (body && body->m_rigidBody)
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_RESTITUTION)
|
||||
{
|
||||
body->m_rigidBody->setRestitution(restitution);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
body->m_rigidBody->setFriction(lateralFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION)
|
||||
{
|
||||
body->m_rigidBody->setSpinningFriction(spinningFriction);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION)
|
||||
{
|
||||
body->m_rigidBody->setRollingFriction(rollingFriction);
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_MASS)
|
||||
{
|
||||
btVector3 localInertia;
|
||||
if (body->m_rigidBody->getCollisionShape())
|
||||
{
|
||||
body->m_rigidBody->getCollisionShape()->calculateLocalInertia(mass,localInertia);
|
||||
}
|
||||
body->m_rigidBody->setMassProps(mass,localInertia);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION)
|
||||
{
|
||||
int bodyUniqueId = clientCmd.m_changeDynamicsInfoArgs.m_bodyUniqueId;
|
||||
int linkIndex = clientCmd.m_changeDynamicsInfoArgs.m_linkIndex;
|
||||
double lateralFriction = clientCmd.m_changeDynamicsInfoArgs.m_lateralFriction;
|
||||
btAssert(bodyUniqueId >= 0);
|
||||
btAssert(linkIndex >= -1);
|
||||
|
||||
InteralBodyData* body = m_data->m_bodyHandles.getHandle(bodyUniqueId);
|
||||
if (body && body->m_multiBody)
|
||||
{
|
||||
btMultiBody* mb = body->m_multiBody;
|
||||
if (linkIndex == -1)
|
||||
{
|
||||
mb->getBaseCollider()->setFriction(lateralFriction);
|
||||
}
|
||||
else
|
||||
{
|
||||
mb->getLinkCollider(linkIndex)->setFriction(lateralFriction);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
SharedMemoryStatus& serverCmd =serverStatusOut;
|
||||
serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
|
||||
@@ -4070,6 +4140,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = clientCmd.m_physSimParamArgs.m_defaultContactERP;
|
||||
}
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD)
|
||||
{
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_restitutionVelocityThreshold = clientCmd.m_physSimParamArgs.m_restitutionVelocityThreshold;
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_ENABLE_FILE_CACHING)
|
||||
{
|
||||
|
||||
@@ -114,6 +114,9 @@ enum EnumChangeDynamicsInfoFlags
|
||||
CHANGE_DYNAMICS_INFO_SET_MASS=1,
|
||||
CHANGE_DYNAMICS_INFO_SET_COM=2,
|
||||
CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION=4,
|
||||
CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION=8,
|
||||
CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION=16,
|
||||
CHANGE_DYNAMICS_INFO_SET_RESTITUTION=32,
|
||||
};
|
||||
|
||||
struct ChangeDynamicsInfoArgs
|
||||
@@ -123,6 +126,9 @@ struct ChangeDynamicsInfoArgs
|
||||
double m_mass;
|
||||
double m_COM[3];
|
||||
double m_lateralFriction;
|
||||
double m_spinningFriction;
|
||||
double m_rollingFriction;
|
||||
double m_restitution;
|
||||
};
|
||||
|
||||
struct GetDynamicsInfoArgs
|
||||
@@ -354,6 +360,8 @@ enum EnumSimParamUpdateFlags
|
||||
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
|
||||
SIM_PARAM_MAX_CMD_PER_1MS = 2048,
|
||||
SIM_PARAM_ENABLE_FILE_CACHING = 4096,
|
||||
SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD = 8192,
|
||||
|
||||
|
||||
};
|
||||
|
||||
@@ -387,6 +395,7 @@ struct SendPhysicsSimulationParameters
|
||||
double m_defaultContactERP;
|
||||
int m_collisionFilterMode;
|
||||
int m_enableFileCaching;
|
||||
double m_restitutionVelocityThreshold;
|
||||
};
|
||||
|
||||
struct LoadBunnyArgs
|
||||
|
||||
Reference in New Issue
Block a user