Merge branch 'master' of git://github.com/bulletphysics/bullet3 into addFovToRenderImage
This commit is contained in:
@@ -172,6 +172,8 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
|
||||
&startOrnX,&startOrnY,&startOrnZ, &startOrnW))
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (strlen(urdfFileName))
|
||||
{
|
||||
// printf("(%f, %f, %f) (%f, %f, %f, %f)\n", startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW);
|
||||
|
||||
@@ -185,12 +187,16 @@ pybullet_loadURDF(PyObject* self, PyObject* args)
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
if (statusType!=CMD_URDF_LOADING_COMPLETED)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Cannot load URDF file.");
|
||||
return NULL;
|
||||
}
|
||||
{
|
||||
PyErr_SetString(SpamError, "Cannot load URDF file.");
|
||||
return NULL;
|
||||
}
|
||||
bodyIndex = b3GetStatusBodyIndex(statusHandle);
|
||||
}
|
||||
} else
|
||||
{
|
||||
PyErr_SetString(SpamError, "Empty filename, method expects 1, 4 or 8 arguments.");
|
||||
return NULL;
|
||||
}
|
||||
return PyLong_FromLong(bodyIndex);
|
||||
}
|
||||
|
||||
@@ -368,8 +374,8 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args)
|
||||
{
|
||||
case CONTROL_MODE_VELOCITY:
|
||||
{
|
||||
double kd = gains;
|
||||
b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetValue);
|
||||
double kd = gains;
|
||||
b3JointControlSetKd(commandHandle,info.m_uIndex,kd);
|
||||
b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce);
|
||||
break;
|
||||
@@ -383,8 +389,8 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args)
|
||||
|
||||
case CONTROL_MODE_POSITION_VELOCITY_PD:
|
||||
{
|
||||
double kp = gains;
|
||||
b3JointControlSetDesiredPosition( commandHandle, info.m_qIndex, targetValue);
|
||||
double kp = gains;
|
||||
b3JointControlSetKp(commandHandle,info.m_uIndex,kp);
|
||||
b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce);
|
||||
break;
|
||||
@@ -1283,10 +1289,12 @@ static PyObject* pybullet_applyExternalTorque(PyObject* self, PyObject* args)
|
||||
PyErr_SetString(SpamError, "flag has to be either WORLD_FRAME or LINK_FRAME");
|
||||
return NULL;
|
||||
}
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
b3SharedMemoryCommandHandle command = b3ApplyExternalForceCommandInit(sm);
|
||||
b3ApplyExternalTorque(command,objectUniqueId,-1,torque, flags);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
{
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
b3SharedMemoryCommandHandle command = b3ApplyExternalForceCommandInit(sm);
|
||||
b3ApplyExternalTorque(command,objectUniqueId,-1,torque, flags);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1402,12 +1410,13 @@ static PyObject* pybullet_getEulerFromQuaternion(PyObject* self, PyObject* args)
|
||||
|
||||
{
|
||||
double rpy[3];
|
||||
sqx = quat[0] * quat[0];
|
||||
double sarg;
|
||||
sqx = quat[0] * quat[0];
|
||||
sqy = quat[1] * quat[1];
|
||||
sqz = quat[2] * quat[2];
|
||||
squ = quat[3] * quat[3];
|
||||
rpy[0] = atan2(2 * (quat[1]*quat[2] + quat[3]*quat[0]), squ - sqx - sqy + sqz);
|
||||
double sarg = -2 * (quat[0]*quat[2] - quat[3] * quat[1]);
|
||||
sarg = -2 * (quat[0]*quat[2] - quat[3] * quat[1]);
|
||||
rpy[1] = sarg <= -1.0 ? -0.5*3.141592538 : (sarg >= 1.0 ? 0.5*3.141592538 : asin(sarg));
|
||||
rpy[2] = atan2(2 * (quat[0]*quat[1] + quat[3]*quat[2]), squ + sqx - sqy - sqz);
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user