summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorChuyuan Fu <fuchuyuan.kelly@gmail.com>2019-03-25 14:12:00 -0700
committerChuyuan Fu <fuchuyuan.kelly@gmail.com>2019-03-25 14:12:00 -0700
commit19f3ec8b804183611859d502983c223ee5c55f8a (patch)
tree6c3442912caf16305069553e9dfc71225f8fb563
parent3768bbcae3c603d7cf9d4352aa42d6205f930444 (diff)
parent2ca6172f1ab957b0123f07cfd84b9e7443019213 (diff)
downloadbullet3-19f3ec8b804183611859d502983c223ee5c55f8a.tar.gz
fix conflut
-rw-r--r--examples/BulletRobotics/FixJointBoxes.cpp16
-rw-r--r--examples/pybullet/pybullet.c6
2 files changed, 9 insertions, 13 deletions
diff --git a/examples/BulletRobotics/FixJointBoxes.cpp b/examples/BulletRobotics/FixJointBoxes.cpp
index a5a89e329..410b1e017 100644
--- a/examples/BulletRobotics/FixJointBoxes.cpp
+++ b/examples/BulletRobotics/FixJointBoxes.cpp
@@ -61,11 +61,7 @@ public:
b3RobotSimulatorLoadUrdfFileArgs args;
b3RobotSimulatorChangeDynamicsArgs dynamicsArgs;
- for (int i = 0; i < numCubes; i++)
- {
- 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()
{
- float dist = 1;
- float pitch = -20;
- float yaw = -30;
- float targetPos[3] = {0, 0.2, 0.5};
- m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
+ float dist = 1;
+ float pitch = -20;
+ float yaw = -30;
+ float targetPos[3] = {0, 0.2, 0.5};
+ m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
};
diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c
index 26f73083e..301d43164 100644
--- a/examples/pybullet/pybullet.c
+++ b/examples/pybullet/pybullet.c
@@ -1243,11 +1243,11 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
PyObject* localInertiaDiagonalObj = 0;
PyObject* anisotropicFrictionObj = 0;
double maxJointVelocity = -1;
-
+
b3PhysicsClientHandle sm = 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))
{
return NULL;
@@ -1340,7 +1340,7 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
{
b3ChangeDynamicsInfoSetMaxJointVelocity(command, bodyUniqueId, maxJointVelocity);
}
-
+
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
}