Add API to reset lateral friction coefficient.

This commit is contained in:
yunfeibai
2017-05-03 21:47:53 -07:00
parent 1841a41f2a
commit 939d6ead32
8 changed files with 54 additions and 4 deletions

View File

@@ -1240,6 +1240,17 @@ int b3ResetDynamicInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bod
return 0; return 0;
} }
int b3ResetDynamicInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_RESET_DYNAMIC_INFO);
command->m_resetDynamicInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_resetDynamicInfoArgs.m_linkIndex = linkIndex;
command->m_resetDynamicInfoArgs.m_lateralFriction = lateralFriction;
command->m_updateFlags |= RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION;
return 0;
}
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info) b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info)
{ {
PhysicsClient* cl = (PhysicsClient* ) physClient; PhysicsClient* cl = (PhysicsClient* ) physClient;

View File

@@ -80,6 +80,7 @@ int b3GetDynamicInfo(b3PhysicsClientHandle physClient, int bodyUniqueId, int lin
b3SharedMemoryCommandHandle b3InitResetDynamicInfo(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3InitResetDynamicInfo(b3PhysicsClientHandle physClient);
int b3ResetDynamicInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass); int b3ResetDynamicInfoSetMass(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double mass);
int b3ResetDynamicInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction);
b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info); b3SharedMemoryCommandHandle b3InitCreateUserConstraintCommand(b3PhysicsClientHandle physClient, int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, struct b3JointInfo* info);

View File

@@ -3759,6 +3759,30 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
} }
} }
if (clientCmd.m_updateFlags & RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION)
{
int bodyUniqueId = clientCmd.m_resetDynamicInfoArgs.m_bodyUniqueId;
int linkIndex = clientCmd.m_resetDynamicInfoArgs.m_linkIndex;
double lateralFriction = clientCmd.m_resetDynamicInfoArgs.m_lateralFriction;
btAssert(bodyUniqueId >= 0);
btAssert(linkIndex >= -1);
InteralBodyData* body = m_data->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; SharedMemoryStatus& serverCmd =serverStatusOut;
serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
hasStatus = true; hasStatus = true;

View File

@@ -110,6 +110,7 @@ enum EnumResetDynamicInfoFlags
{ {
RESET_DYNAMIC_INFO_SET_MASS=1, RESET_DYNAMIC_INFO_SET_MASS=1,
RESET_DYNAMIC_INFO_SET_COM=2, RESET_DYNAMIC_INFO_SET_COM=2,
RESET_DYNAMIC_INFO_SET_LATERAL_FRICTION=4,
}; };
struct ResetDynamicInfoArgs struct ResetDynamicInfoArgs
@@ -118,6 +119,7 @@ struct ResetDynamicInfoArgs
int m_linkIndex; int m_linkIndex;
double m_mass; double m_mass;
double m_COM[3]; double m_COM[3];
double m_lateralFriction;
}; };
struct SetJointFeedbackArgs struct SetJointFeedbackArgs

View File

@@ -212,7 +212,6 @@ struct b3DynamicInfo
{ {
double m_mass; double m_mass;
double m_localInertialPosition[3]; double m_localInertialPosition[3];
double m_localInertialOrientation[4];
}; };
// copied from btMultiBodyLink.h // copied from btMultiBodyLink.h

View File

@@ -14,5 +14,7 @@ p.setRealTimeSimulation(0)
t=0 t=0
while 1: while 1:
t=t+1 t=t+1
if t > 400:
p.resetDynamicInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
time.sleep(.01) time.sleep(.01)
p.stepSimulation() p.stepSimulation()

View File

@@ -609,11 +609,12 @@ static PyObject* pybullet_resetDynamicInfo(PyObject* self, PyObject* args, PyObj
int bodyUniqueId = -1; int bodyUniqueId = -1;
int linkIndex = -2; int linkIndex = -2;
double mass = -1; double mass = -1;
double lateralFriction = -1;
b3PhysicsClientHandle sm = 0; b3PhysicsClientHandle sm = 0;
int physicsClientId = 0; int physicsClientId = 0;
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "physicsClientId", NULL}; static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|di", kwlist, &bodyUniqueId, &linkIndex,&mass, &physicsClientId)) if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ddi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &physicsClientId))
{ {
return NULL; return NULL;
} }
@@ -634,6 +635,11 @@ static PyObject* pybullet_resetDynamicInfo(PyObject* self, PyObject* args, PyObj
b3ResetDynamicInfoSetMass(command, bodyUniqueId, linkIndex, mass); b3ResetDynamicInfoSetMass(command, bodyUniqueId, linkIndex, mass);
} }
if (lateralFriction >= 0)
{
b3ResetDynamicInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
} }
@@ -5504,7 +5510,7 @@ static PyMethodDef SpamMethods[] = {
"instantaneously, not through physics simulation."}, "instantaneously, not through physics simulation."},
{"resetDynamicInfo", (PyCFunction)pybullet_resetDynamicInfo, METH_VARARGS | METH_KEYWORDS, {"resetDynamicInfo", (PyCFunction)pybullet_resetDynamicInfo, METH_VARARGS | METH_KEYWORDS,
"Reset dynamic information such as mass, COM."}, "Reset dynamic information such as mass, lateral friction coefficient."},
{"setJointMotorControl", (PyCFunction)pybullet_setJointMotorControl, METH_VARARGS, {"setJointMotorControl", (PyCFunction)pybullet_setJointMotorControl, METH_VARARGS,
"This (obsolete) method cannot select non-zero physicsClientId, use setJointMotorControl2 instead." "This (obsolete) method cannot select non-zero physicsClientId, use setJointMotorControl2 instead."

View File

@@ -140,6 +140,11 @@ public:
return m_baseCollider; return m_baseCollider;
} }
btMultiBodyLinkCollider* getLinkCollider(int index)
{
return m_colliders[index];
}
// //
// get parent // get parent
// input: link num from 0 to num_links-1 // input: link num from 0 to num_links-1