OpenVR controller can pick/drag objects. Instructions, Windows only:

Compile using premake+visual studio, and compile App_SharedMemoryPhysics_VR
Compile pybullet using cmake using cmake -DBUILD_PYBULLET=OFF -DCMAKE_BUILD_TYPE=Release ..
Create a symbolic link from c:\python\dlls\pybullet.pyd to C:\develop\bullet3\cmp\lib\Release\pybullet.dll
App_SharedMemoryPhysics_VR
Run Python. Here are some Python lines to get going:
import pybullet as p
p.connect(p.SHARED_MEMORY)
p.loadURDF("cube.urdf")
p.setGravity(0,0,-10)
p.setRealTimeSimulation(1)

Allow real-time simulation in physics server, add pybullet command setRealTimeSimulation to control it
Mesh decimation (reduce number of triangles/vertices) using a Blender modifier for Kuka IIWA and Husky
Disabled the 'glFlush' commands in GLInstancingRenderer.
Add VR controller methods to examples\CommonInterfaces\CommonExampleInterface.h
Use the ANSI version in Windows file/string operations instead of unicode, hope this doesn't break builds.
This commit is contained in:
erwin coumans
2016-07-17 23:50:11 -07:00
parent e1e76c19a3
commit c28cd03fbd
32 changed files with 295 additions and 50 deletions

View File

@@ -81,6 +81,7 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);
int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep);
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);