Use "change" instead of "reset" for changing dynamics info.
This commit is contained in:
@@ -6,15 +6,15 @@ p.connect(p.GUI)
|
||||
planeId = p.loadURDF(fileName="plane.urdf",baseOrientation=[0.25882,0,0,0.96593])
|
||||
p.loadURDF(fileName="cube.urdf",baseOrientation=[0.25882,0,0,0.96593],basePosition=[0,0,2])
|
||||
cubeId = p.loadURDF(fileName="cube.urdf",baseOrientation=[0,0,0,1],basePosition=[0,0,4])
|
||||
p.resetDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
|
||||
#p.resetDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
|
||||
p.changeDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=0.1)
|
||||
#p.changeDynamicsInfo(bodyUniqueId=2,linkIndex=-1,mass=100.0)
|
||||
p.setGravity(0,0,-10)
|
||||
p.setRealTimeSimulation(0)
|
||||
t=0
|
||||
while 1:
|
||||
t=t+1
|
||||
if t > 400:
|
||||
p.resetDynamicsInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
|
||||
p.changeDynamicsInfo(bodyUniqueId=0,linkIndex=-1,lateralFriction=0.01)
|
||||
mass1,frictionCoeff1=p.getDynamicsInfo(bodyUniqueId=planeId,linkIndex=-1)
|
||||
mass2,frictionCoeff2=p.getDynamicsInfo(bodyUniqueId=cubeId,linkIndex=-1)
|
||||
print mass1,frictionCoeff1
|
||||
|
||||
@@ -604,7 +604,7 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* key
|
||||
return pylist;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_resetDynamicsInfo(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int bodyUniqueId = -1;
|
||||
int linkIndex = -2;
|
||||
@@ -627,17 +627,17 @@ static PyObject* pybullet_resetDynamicsInfo(PyObject* self, PyObject* args, PyOb
|
||||
}
|
||||
|
||||
{
|
||||
b3SharedMemoryCommandHandle command = b3InitResetDynamicsInfo(sm);
|
||||
b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(sm);
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
|
||||
if (mass >= 0)
|
||||
{
|
||||
b3ResetDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass);
|
||||
b3ChangeDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass);
|
||||
}
|
||||
|
||||
if (lateralFriction >= 0)
|
||||
{
|
||||
b3ResetDynamicsInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
|
||||
b3ChangeDynamicsInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
@@ -5639,8 +5639,8 @@ static PyMethodDef SpamMethods[] = {
|
||||
"Reset the state (position, velocity etc) for a joint on a body "
|
||||
"instantaneously, not through physics simulation."},
|
||||
|
||||
{"resetDynamicsInfo", (PyCFunction)pybullet_resetDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
"Reset dynamics information such as mass, lateral friction coefficient."},
|
||||
{"changeDynamicsInfo", (PyCFunction)pybullet_changeDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
"change dynamics information such as mass, lateral friction coefficient."},
|
||||
|
||||
{"getDynamicsInfo", (PyCFunction)pybullet_getDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
|
||||
"Get dynamics information such as mass, lateral friction coefficient."},
|
||||
|
||||
Reference in New Issue
Block a user