fix conflut
This commit is contained in:
@@ -61,11 +61,7 @@ public:
|
|||||||
b3RobotSimulatorLoadUrdfFileArgs args;
|
b3RobotSimulatorLoadUrdfFileArgs args;
|
||||||
b3RobotSimulatorChangeDynamicsArgs dynamicsArgs;
|
b3RobotSimulatorChangeDynamicsArgs dynamicsArgs;
|
||||||
|
|
||||||
for (int i = 0; i < numCubes; i++)
|
b3RobotJointInfo jointInfo;
|
||||||
{
|
|
||||||
args.m_forceOverrideFixedBase = (i == 0);
|
|
||||||
args.m_startPosition.setValue(0, i * 0.05, 1);
|
|
||||||
cubeIds[i] = m_robotSim.loadURDF("cube_small.urdf", args);
|
|
||||||
|
|
||||||
b3RobotJointInfo jointInfo;
|
b3RobotJointInfo jointInfo;
|
||||||
|
|
||||||
@@ -158,11 +154,11 @@ public:
|
|||||||
|
|
||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1;
|
float dist = 1;
|
||||||
float pitch = -20;
|
float pitch = -20;
|
||||||
float yaw = -30;
|
float yaw = -30;
|
||||||
float targetPos[3] = {0, 0.2, 0.5};
|
float targetPos[3] = {0, 0.2, 0.5};
|
||||||
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -1243,11 +1243,11 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
|||||||
PyObject* localInertiaDiagonalObj = 0;
|
PyObject* localInertiaDiagonalObj = 0;
|
||||||
PyObject* anisotropicFrictionObj = 0;
|
PyObject* anisotropicFrictionObj = 0;
|
||||||
double maxJointVelocity = -1;
|
double maxJointVelocity = -1;
|
||||||
|
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
|
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction", "restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "activationState", "jointDamping", "anisotropicFriction", "maxJointVelocity", "physicsClientId", NULL};
|
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction", "restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "activationState", "jointDamping", "anisotropicFriction", "maxJointVelocity", "physicsClientId", NULL};
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddidOdi", kwlist, &bodyUniqueId, &linkIndex, &mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution, &linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold, &activationState, &jointDamping, &anisotropicFrictionObj, &maxJointVelocity, &physicsClientId))
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddidOdi", kwlist, &bodyUniqueId, &linkIndex, &mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution, &linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold, &activationState, &jointDamping, &anisotropicFrictionObj, &maxJointVelocity, &physicsClientId))
|
||||||
{
|
{
|
||||||
return NULL;
|
return NULL;
|
||||||
@@ -1340,7 +1340,7 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
|||||||
{
|
{
|
||||||
b3ChangeDynamicsInfoSetMaxJointVelocity(command, bodyUniqueId, maxJointVelocity);
|
b3ChangeDynamicsInfoSetMaxJointVelocity(command, bodyUniqueId, maxJointVelocity);
|
||||||
}
|
}
|
||||||
|
|
||||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user