diff --git a/data/sphere2_rolling_friction.urdf b/data/sphere2_rolling_friction.urdf index e4ff66341..e5785e3cd 100644 --- a/data/sphere2_rolling_friction.urdf +++ b/data/sphere2_rolling_friction.urdf @@ -3,6 +3,7 @@ + diff --git a/docs/pybullet_quickstartguide.pdf b/docs/pybullet_quickstartguide.pdf index 8f49ec179..56cdb8af6 100644 Binary files a/docs/pybullet_quickstartguide.pdf and b/docs/pybullet_quickstartguide.pdf differ diff --git a/examples/Benchmarks/BenchmarkDemo.cpp b/examples/Benchmarks/BenchmarkDemo.cpp index fdacc0347..d9a1b3ef0 100644 --- a/examples/Benchmarks/BenchmarkDemo.cpp +++ b/examples/Benchmarks/BenchmarkDemo.cpp @@ -210,9 +210,13 @@ public: { for ( int i = iBegin; i < iEnd; ++i ) { + btCollisionWorld::ClosestRayResultCallback cb(source[i], dest[i]); - cw->rayTest (source[i], dest[i], cb); + { + BT_PROFILE("cw->rayTest"); + cw->rayTest(source[i], dest[i], cb); + } if (cb.hasHit ()) { hit[i] = cb.m_hitPointWorld; @@ -241,6 +245,8 @@ public: void cast (btCollisionWorld* cw, bool multiThreading = false) { + BT_PROFILE("cast"); + #ifdef USE_BT_CLOCK frame_timer.reset (); #endif //USE_BT_CLOCK diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index db8f3c498..37cf5eb70 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -295,8 +295,19 @@ bool UrdfParser::parseInertia(UrdfInertia& inertia, TiXmlElement* config, ErrorL inertia.m_izz = urdfLexicalCast(izz->GetText()); } else { - logger->reportError("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz child elements"); - return false; + if (ixx && iyy && izz) + { + inertia.m_ixx = urdfLexicalCast(ixx->GetText()); + inertia.m_ixy = 0; + inertia.m_ixz = 0; + inertia.m_iyy = urdfLexicalCast(iyy->GetText()); + inertia.m_iyz = 0; + inertia.m_izz = urdfLexicalCast(izz->GetText()); + } else + { + logger->reportError("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz child elements"); + return false; + } } } else { @@ -304,15 +315,29 @@ bool UrdfParser::parseInertia(UrdfInertia& inertia, TiXmlElement* config, ErrorL inertia_xml->Attribute("iyy") && inertia_xml->Attribute("iyz") && inertia_xml->Attribute("izz"))) { - logger->reportError("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz attributes"); - return false; - } - inertia.m_ixx = urdfLexicalCast(inertia_xml->Attribute("ixx")); - inertia.m_ixy = urdfLexicalCast(inertia_xml->Attribute("ixy")); - inertia.m_ixz = urdfLexicalCast(inertia_xml->Attribute("ixz")); - inertia.m_iyy = urdfLexicalCast(inertia_xml->Attribute("iyy")); - inertia.m_iyz = urdfLexicalCast(inertia_xml->Attribute("iyz")); - inertia.m_izz = urdfLexicalCast(inertia_xml->Attribute("izz")); + if ((inertia_xml->Attribute("ixx") && inertia_xml->Attribute("iyy") && + inertia_xml->Attribute("izz"))) + { + inertia.m_ixx = urdfLexicalCast(inertia_xml->Attribute("ixx")); + inertia.m_ixy = 0; + inertia.m_ixz = 0; + inertia.m_iyy = urdfLexicalCast(inertia_xml->Attribute("iyy")); + inertia.m_iyz = 0; + inertia.m_izz = urdfLexicalCast(inertia_xml->Attribute("izz")); + } else + { + logger->reportError("Inertial: inertia element must have ixx,ixy,ixz,iyy,iyz,izz attributes"); + return false; + } + } else + { + inertia.m_ixx = urdfLexicalCast(inertia_xml->Attribute("ixx")); + inertia.m_ixy = urdfLexicalCast(inertia_xml->Attribute("ixy")); + inertia.m_ixz = urdfLexicalCast(inertia_xml->Attribute("ixz")); + inertia.m_iyy = urdfLexicalCast(inertia_xml->Attribute("iyy")); + inertia.m_iyz = urdfLexicalCast(inertia_xml->Attribute("iyz")); + inertia.m_izz = urdfLexicalCast(inertia_xml->Attribute("izz")); + } } return true; diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp index 6a7634618..17c5f802d 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp @@ -611,6 +611,7 @@ btConstraintSolver* createSolverByType( SolverType t ) case SOLVER_TYPE_MLCP_LEMKE: mlcpSolver = new btLemkeSolver(); break; + default: {} } if (mlcpSolver) { diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h index a399c032e..0695b88c0 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.h @@ -31,6 +31,7 @@ inline const char* getSolverTypeName( SolverType t ) case SOLVER_TYPE_MLCP_PGS: return "MLCP ProjectedGaussSeidel"; case SOLVER_TYPE_MLCP_DANTZIG: return "MLCP Dantzig"; case SOLVER_TYPE_MLCP_LEMKE: return "MLCP Lemke"; + default:{} } btAssert( !"unhandled solver type in switch" ); return "???"; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 40e60c3bb..913fe086b 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -189,6 +189,11 @@ struct b3BodyInfo }; +// copied from btMultiBodyLink.h +enum SensorType { + eSensorForceTorqueType = 1, +}; + struct b3JointSensorState { diff --git a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp index 16b0522ea..7483936ba 100644 --- a/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp +++ b/examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp @@ -211,7 +211,7 @@ updateVertex( positions.push_back(in_positions[3*i.v_idx+1]); positions.push_back(in_positions[3*i.v_idx+2]); - if (i.vn_idx >= 0) { + if (i.vn_idx >= 0 && ((3*i.vn_idx+2)= numJoints)) + { + PyErr_SetString(SpamError, "Error: invalid jointIndex."); + return NULL; + } + + { + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + + commandHandle = b3CreateSensorCommandInit(sm, bodyUniqueId); + b3CreateSensorEnable6DofJointForceTorqueSensor(commandHandle, jointIndex, enableSensor); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_CLIENT_COMMAND_COMPLETED) + { + Py_INCREF(Py_None); + return Py_None; + } + } + + PyErr_SetString(SpamError, "Error creating sensor."); + return NULL; +} + + static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) { @@ -3455,15 +3525,11 @@ static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, P int userConstraintUid = b3GetStatusUserConstraintUniqueId(statusHandle); PyObject* ob = PyLong_FromLong(userConstraintUid); return ob; - } else - { - PyErr_SetString(SpamError, "createConstraint failed."); - return NULL; } - Py_INCREF(Py_None); - return Py_None; + PyErr_SetString(SpamError, "createConstraint failed."); + return NULL; } static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, PyObject *keywds) { @@ -4690,6 +4756,10 @@ static PyMethodDef SpamMethods[] = { "Remove a constraint using its unique id." }, + { "enableJointForceTorqueSensor", (PyCFunction)pybullet_enableJointForceTorqueSensor, METH_VARARGS | METH_KEYWORDS, + "Enable or disable a joint force/torque sensor measuring the joint reaction forces." + }, + {"saveWorld", (PyCFunction)pybullet_saveWorld, METH_VARARGS| METH_KEYWORDS, "Save a approximate Python file to reproduce the current state of the world: saveWorld" "(filename). (very preliminary and approximately)"}, @@ -4868,7 +4938,7 @@ static PyMethodDef SpamMethods[] = { "Convert quaternion [x,y,z,w] to Euler [roll, pitch, yaw] as in URDF/SDF " "convention"}, - {"getMatrixFromQuaterion", pybullet_getMatrixFromQuaterion,METH_VARARGS, + {"getMatrixFromQuaternion", pybullet_getMatrixFromQuaternion,METH_VARARGS, "Compute the 3x3 matrix from a quaternion, as a list of 9 values (row-major)"}, {"calculateInverseDynamics", (PyCFunction)pybullet_calculateInverseDynamics, METH_VARARGS| METH_KEYWORDS, @@ -4954,6 +5024,9 @@ initpybullet(void) PyModule_AddIntConstant(m, "JOINT_FIXED", eFixedType); // user read PyModule_AddIntConstant(m, "JOINT_POINT2POINT", ePoint2PointType); // user read + PyModule_AddIntConstant(m, "SENSOR_FORCE_TORQUE", eSensorForceTorqueType); // user read + + PyModule_AddIntConstant(m, "TORQUE_CONTROL", CONTROL_MODE_TORQUE); PyModule_AddIntConstant(m, "VELOCITY_CONTROL", CONTROL_MODE_VELOCITY); // user read