This commit is contained in:
Erwin Coumans
2017-05-17 21:22:30 -07:00
13 changed files with 204 additions and 39 deletions

Binary file not shown.

View File

@@ -7,7 +7,7 @@
#include "../../Utils/b3ResourcePath.h"
#include "Bullet3Common/b3FileUtils.h"
#include "../../ThirdPartyLibs/stb_image/stb_image.h"
#include "../ImportObjDemo/LoadMeshFromObj.h"
bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData)
{
B3_PROFILE("loadAndRegisterMeshFromFileInternal");
@@ -28,7 +28,8 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
std::vector<tinyobj::shape_t> shapes;
{
B3_PROFILE("tinyobj::LoadObj");
std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
std::string err = LoadFromCachedOrFromObj(shapes, relativeFileName, pathPrefix);
//std::string err = tinyobj::LoadObj(shapes, relativeFileName, pathPrefix);
}
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);

View File

@@ -1,11 +1,56 @@
#include "LoadMeshFromObj.h"
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
#include "../../OpenGLWindow/GLInstanceGraphicsShape.h"
#include <stdio.h> //fopen
#include "Bullet3Common/b3AlignedObjectArray.h"
#include <string>
#include <vector>
#include "Wavefront2GLInstanceGraphicsShape.h"
#include "Bullet3Common/b3HashMap.h"
struct CachedObjResult
{
std::string m_msg;
std::vector<tinyobj::shape_t> m_shapes;
};
static b3HashMap<b3HashString, CachedObjResult> gCachedObjResults;
static int gEnableFileCaching = 1;
void b3EnableFileCaching(int enable)
{
gEnableFileCaching = enable;
if (enable==0)
{
gCachedObjResults.clear();
}
}
std::string LoadFromCachedOrFromObj(
std::vector<tinyobj::shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath)
{
CachedObjResult* resultPtr = gCachedObjResults[filename];
if (resultPtr)
{
const CachedObjResult& result = *resultPtr;
shapes = result.m_shapes;
return result.m_msg;
}
std::string err = tinyobj::LoadObj(shapes, filename, mtl_basepath);
CachedObjResult result;
result.m_msg = err;
result.m_shapes = shapes;
if (gEnableFileCaching)
{
gCachedObjResults.insert(filename,result);
}
return err;
}
GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const char* materialPrefixPath)
{
@@ -13,7 +58,7 @@ GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const cha
std::vector<tinyobj::shape_t> shapes;
{
B3_PROFILE("tinyobj::LoadObj2");
std::string err = tinyobj::LoadObj(shapes, relativeFileName, materialPrefixPath);
std::string err = LoadFromCachedOrFromObj(shapes, relativeFileName, materialPrefixPath);
}
{

View File

@@ -4,6 +4,14 @@
struct GLInstanceGraphicsShape;
#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h"
void b3EnableFileCaching(int enable);
std::string LoadFromCachedOrFromObj(
std::vector<tinyobj::shape_t>& shapes, // [output]
const char* filename,
const char* mtl_basepath);
GLInstanceGraphicsShape* LoadMeshFromObj(const char* relativeFileName, const char* materialPrefixPath);

View File

@@ -634,8 +634,15 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
case UrdfGeometry::FILE_OBJ:
if (collision->m_flags & URDF_FORCE_CONCAVE_TRIMESH)
{
glmesh = LoadMeshFromObj(collision->m_geometry.m_meshFileName.c_str(), 0);
char relativeFileName[1024];
char pathPrefix[1024];
pathPrefix[0] = 0;
if (b3ResourcePath::findResourcePath(collision->m_geometry.m_meshFileName.c_str(), relativeFileName, 1024))
{
b3FileUtils::extractPath(relativeFileName, pathPrefix, 1024);
}
glmesh = LoadMeshFromObj(collision->m_geometry.m_meshFileName.c_str(), pathPrefix);
}
else
{

View File

@@ -381,6 +381,17 @@ int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHan
}
int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_enableFileCaching= enableFileCaching;
command->m_updateFlags |= SIM_PARAM_ENABLE_FILE_CACHING ;
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
@@ -1785,7 +1796,10 @@ void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandl
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
b3Assert(renderer>(1<<15));
command->m_updateFlags |= renderer;
if (renderer>(1<<15))
{
command->m_updateFlags |= renderer;
}
}
void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
@@ -2712,6 +2726,8 @@ int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, doub
command->m_vrCameraStateArguments.m_rootOrientation[0] = rootOrn[0];
command->m_vrCameraStateArguments.m_rootOrientation[1] = rootOrn[1];
command->m_vrCameraStateArguments.m_rootOrientation[2] = rootOrn[2];
command->m_vrCameraStateArguments.m_rootOrientation[3] = rootOrn[3];
return 0;
}
@@ -2725,6 +2741,15 @@ int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int o
return 0;
}
int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_SET_VR_CAMERA_STATE);
command->m_updateFlags |= VR_CAMERA_FLAG;
command->m_vrCameraStateArguments.m_trackingObjectFlag = flag;
return 0;
}
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient)

View File

@@ -215,6 +215,7 @@ int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle,
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
int b3PhysicsParamSetMaxNumCommandsPer1ms(b3SharedMemoryCommandHandle commandHandle, int maxNumCmdPer1ms);
int b3PhysicsParamSetEnableFileCaching(b3SharedMemoryCommandHandle commandHandle, int enableFileCaching);
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
//Use at own risk: magic things may or my not happen when calling this API
@@ -376,6 +377,7 @@ b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle
int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double rootPos[3]);
int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]);
int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
int b3SetVRCameraTrackingObjectFlag(b3SharedMemoryCommandHandle commandHandle, int flag);
b3SharedMemoryCommandHandle b3RequestKeyboardEventsCommandInit(b3PhysicsClientHandle physClient);
void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3KeyboardEventsData* keyboardEventsData);

View File

@@ -22,6 +22,7 @@
#include "../Utils/RobotLoggingUtil.h"
#include "LinearMath/btTransform.h"
#include "../Importers/ImportMJCFDemo/BulletMJCFImporter.h"
#include "../Importers/ImportObjDemo/LoadMeshFromObj.h"
#include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
#include "LinearMath/btSerializer.h"
@@ -54,6 +55,8 @@ bool gCreateDefaultRobotAssets = false;
int gInternalSimFlags = 0;
bool gResetSimulation = 0;
int gVRTrackingObjectUniqueId = -1;
int gVRTrackingObjectFlag = VR_CAMERA_TRACK_OBJECT_ORIENTATION;
btTransform gVRTrackingObjectTr = btTransform::getIdentity();
int gMaxNumCmdPer1ms = -1;//experiment: add some delay to avoid threads starving other threads
@@ -2440,6 +2443,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
if (clientCmd.m_stateLoggingArguments.m_loggingUniqueId == m_data->m_profileTimingLoggingUid)
{
serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED;
b3ChromeUtilsStopTimingsAndWriteJsonFile(m_data->m_profileTimingFileName.c_str());
m_data->m_profileTimingLoggingUid = -1;
}
@@ -2482,6 +2486,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
gVRTrackingObjectUniqueId = clientCmd.m_vrCameraStateArguments.m_trackingObjectUniqueId;
}
if (clientCmd.m_updateFlags & VR_CAMERA_FLAG)
{
gVRTrackingObjectFlag = clientCmd.m_vrCameraStateArguments.m_trackingObjectFlag;
}
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
hasStatus = true;
break;
@@ -4059,6 +4068,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = clientCmd.m_physSimParamArgs.m_defaultContactERP;
}
if (clientCmd.m_updateFlags&SIM_PARAM_ENABLE_FILE_CACHING)
{
b3EnableFileCaching(clientCmd.m_physSimParamArgs.m_enableFileCaching);
}
SharedMemoryStatus& serverCmd =serverStatusOut;
serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
hasStatus = true;
@@ -6189,6 +6204,24 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
gResetSimulation = false;
}
if (gVRTrackingObjectUniqueId >= 0)
{
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(gVRTrackingObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
{
// gVRTrackingObjectTr = bodyHandle->m_multiBody->getBaseWorldTransform();
if (gVRTrackingObjectUniqueId>=0)
{
gVRTrackingObjectTr.setOrigin(bodyHandle->m_multiBody->getBaseWorldTransform().getOrigin());
}
if (gVRTrackingObjectFlag&VR_CAMERA_TRACK_OBJECT_ORIENTATION)
{
gVRTrackingObjectTr.setBasis(bodyHandle->m_multiBody->getBaseWorldTransform().getBasis());
}
}
}
if ((m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
{
@@ -6208,14 +6241,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const
gSubStep = m_data->m_physicsDeltaTime;
}
if (gVRTrackingObjectUniqueId >= 0)
{
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(gVRTrackingObjectUniqueId);
if (bodyHandle && bodyHandle->m_multiBody)
{
gVRTrackingObjectTr = bodyHandle->m_multiBody->getBaseWorldTransform();
}
}
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);

View File

@@ -353,6 +353,8 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
SIM_PARAM_MAX_CMD_PER_1MS = 2048,
SIM_PARAM_ENABLE_FILE_CACHING = 4096,
};
enum EnumLoadBunnyUpdateFlags
@@ -384,6 +386,7 @@ struct SendPhysicsSimulationParameters
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;
int m_enableFileCaching;
};
struct LoadBunnyArgs
@@ -675,7 +678,8 @@ enum eVRCameraEnums
{
VR_CAMERA_ROOT_POSITION=1,
VR_CAMERA_ROOT_ORIENTATION=2,
VR_CAMERA_ROOT_TRACKING_OBJECT=4
VR_CAMERA_ROOT_TRACKING_OBJECT=4,
VR_CAMERA_FLAG = 8,
};
enum eStateLoggingEnums
@@ -696,6 +700,7 @@ struct VRCameraState
double m_rootPosition[3];
double m_rootOrientation[4];
int m_trackingObjectUniqueId;
int m_trackingObjectFlag;
};

View File

@@ -320,6 +320,11 @@ enum eVRDeviceTypeEnums
VR_DEVICE_GENERIC_TRACKER=4,
};
enum EVRCameraFlags
{
VR_CAMERA_TRACK_OBJECT_ORIENTATION=1,
};
struct b3VRControllerEvent
{
int m_controllerId;//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT

View File

@@ -560,9 +560,12 @@ LoadObj(
int maxchars = 8192; // Alloc enough size.
std::vector<char> buf(maxchars); // Alloc enough size.
std::string linebuf;
linebuf.reserve(maxchars);
while (ifs.peek() != -1) {
std::string linebuf;
linebuf.resize(0);
safeGetline(ifs,linebuf);
// Trim newline '\r\n' or '\r'

View File

@@ -95,6 +95,9 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16])
int i, len;
PyObject* seq;
if (objMat==NULL)
return 0;
seq = PySequence_Fast(objMat, "expected a sequence");
if (seq)
{
@@ -123,6 +126,7 @@ static int pybullet_internalSetVector(PyObject* objVec, float vector[3])
{
int i, len;
PyObject* seq = 0;
if (objVec == NULL)
return 0;
@@ -720,13 +724,15 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
int collisionFilterMode = -1;
double contactBreakingThreshold = -1;
int maxNumCmdPer1ms = -2;
int enableFileCaching = -1;
b3PhysicsClientHandle sm = 0;
int physicsClientId = 0;
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "physicsClientId", NULL};
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &physicsClientId))
{
return NULL;
}
@@ -777,6 +783,11 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
b3PhysicsParamSetMaxNumCommandsPer1ms(command, maxNumCmdPer1ms);
}
if (enableFileCaching>=0)
{
b3PhysicsParamSetEnableFileCaching(command, enableFileCaching);
}
//ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
@@ -3699,11 +3710,12 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj
PyObject* rootPosObj = 0;
PyObject* rootOrnObj = 0;
int trackObjectUid = -2;
int trackObjectFlag = -1;
double rootPos[3];
double rootOrn[4];
static char* kwlist[] = {"rootPosition", "rootOrientation", "trackObject", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|OOii", kwlist, &rootPosObj, &rootOrnObj, &trackObjectUid, &physicsClientId))
static char* kwlist[] = {"rootPosition", "rootOrientation", "trackObject", "trackObjectFlag","physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|OOiii", kwlist, &rootPosObj, &rootOrnObj, &trackObjectUid,&trackObjectFlag, &physicsClientId))
{
return NULL;
}
@@ -3730,6 +3742,11 @@ static PyObject* pybullet_setVRCameraState(PyObject* self, PyObject* args, PyObj
b3SetVRCameraTrackingObject(commandHandle, trackObjectUid);
}
if (trackObjectFlag>=-1)
{
b3SetVRCameraTrackingObjectFlag(commandHandle, trackObjectFlag);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
@@ -4543,7 +4560,7 @@ static PyObject* pybullet_enableJointForceTorqueSensor(PyObject* self, PyObject*
b3PhysicsClientHandle sm = 0;
int numJoints = -1;
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "enableSensor", "physicsClientId"};
static char* kwlist[] = {"bodyUniqueId", "jointIndex", "enableSensor", "physicsClientId",NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ii", kwlist, &bodyUniqueId, &jointIndex, &enableSensor, &physicsClientId))
{
@@ -4755,12 +4772,13 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
float projectionMatrix[16];
float lightDir[3];
float lightColor[3];
float lightDist = 10.0;
int hasShadow = 0;
float lightAmbientCoeff = 0.6;
float lightDiffuseCoeff = 0.35;
float lightSpecularCoeff = 0.05;
int renderer = 0;
float lightDist = -1;
int hasShadow = -1;
float lightAmbientCoeff = -1;
float lightDiffuseCoeff = -1;
float lightSpecularCoeff = -1;
int renderer = -1;
// inialize cmd
b3SharedMemoryCommandHandle command;
int physicsClientId = 0;
@@ -4783,12 +4801,12 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
b3RequestCameraImageSetPixelResolution(command, width, height);
// set camera matrices only if set matrix function succeeds
if (pybullet_internalSetMatrix(objViewMat, viewMatrix) && (pybullet_internalSetMatrix(objProjMat, projectionMatrix)))
if (objViewMat && objProjMat && pybullet_internalSetMatrix(objViewMat, viewMatrix) && (pybullet_internalSetMatrix(objProjMat, projectionMatrix)))
{
b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix);
}
//set light direction only if function succeeds
if (pybullet_internalSetVector(lightDirObj, lightDir))
if (lightDirObj && pybullet_internalSetVector(lightDirObj, lightDir))
{
b3RequestCameraImageSetLightDirection(command, lightDir);
}
@@ -4797,16 +4815,34 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
{
b3RequestCameraImageSetLightColor(command, lightColor);
}
if (lightDist>=0)
{
b3RequestCameraImageSetLightDistance(command, lightDist);
}
b3RequestCameraImageSetLightDistance(command, lightDist);
if (hasShadow>=0)
{
b3RequestCameraImageSetShadow(command, hasShadow);
}
if (lightAmbientCoeff>=0)
{
b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff);
}
if (lightDiffuseCoeff>=0)
{
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
}
b3RequestCameraImageSetShadow(command, hasShadow);
if (lightSpecularCoeff>=0)
{
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
}
b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff);
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
if (renderer>=0)
{
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
}
//PyErr_Clear();
if (b3CanSubmitCommand(sm))
{
@@ -6332,6 +6368,8 @@ initpybullet(void)
PyModule_AddIntConstant(m, "VR_DEVICE_HMD", VR_DEVICE_HMD);
PyModule_AddIntConstant(m, "VR_DEVICE_GENERIC_TRACKER", VR_DEVICE_GENERIC_TRACKER);
PyModule_AddIntConstant(m, "VR_CAMERA_TRACK_OBJECT_ORIENTATION", VR_CAMERA_TRACK_OBJECT_ORIENTATION);
PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown);
PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered);
PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased);

View File

@@ -417,7 +417,7 @@ else:
setup(
name = 'pybullet',
version='1.0.4',
version='1.0.6',
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',