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:
@@ -115,6 +115,15 @@ int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, doub
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
|
||||
command->m_physSimParamArgs.m_allowRealTimeSimulation = enableRealTimeSimulation;
|
||||
command->m_updateFlags |= SIM_PARAM_UPDATE_REAL_TIME_SIMULATION;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -374,6 +374,8 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
|
||||
///end handle management
|
||||
|
||||
bool m_allowRealTimeSimulation;
|
||||
bool m_hasGround;
|
||||
|
||||
CommandLogger* m_commandLogger;
|
||||
CommandLogPlayback* m_logPlayback;
|
||||
@@ -417,7 +419,8 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
TinyRendererVisualShapeConverter m_visualConverter;
|
||||
|
||||
PhysicsServerCommandProcessorInternalData()
|
||||
:
|
||||
:m_hasGround(false),
|
||||
m_allowRealTimeSimulation(false),
|
||||
m_commandLogger(0),
|
||||
m_logPlayback(0),
|
||||
m_physicsDeltaTime(1./240.),
|
||||
@@ -496,6 +499,9 @@ void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiH
|
||||
}
|
||||
}
|
||||
m_data->m_guiHelper = guiHelper;
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -504,6 +510,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
|
||||
m_data = new PhysicsServerCommandProcessorInternalData();
|
||||
|
||||
createEmptyDynamicsWorld();
|
||||
|
||||
}
|
||||
|
||||
PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
|
||||
@@ -983,7 +990,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char*
|
||||
|
||||
bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
|
||||
{
|
||||
|
||||
|
||||
bool hasStatus = false;
|
||||
|
||||
{
|
||||
@@ -1768,6 +1775,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime;
|
||||
}
|
||||
if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION)
|
||||
{
|
||||
m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation;
|
||||
}
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY)
|
||||
{
|
||||
btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0],
|
||||
@@ -1873,7 +1884,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
SharedMemoryStatus& serverCmd =serverStatusOut;
|
||||
serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED;
|
||||
hasStatus = true;
|
||||
|
||||
m_data->m_hasGround = false;
|
||||
break;
|
||||
}
|
||||
case CMD_CREATE_RIGID_BODY:
|
||||
@@ -2307,6 +2318,26 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
|
||||
m_data->m_logPlayback = pb;
|
||||
}
|
||||
|
||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
{
|
||||
if (m_data->m_allowRealTimeSimulation)
|
||||
{
|
||||
if (!m_data->m_hasGround)
|
||||
{
|
||||
m_data->m_hasGround = true;
|
||||
|
||||
int bodyId = 0;
|
||||
btAlignedObjectArray<char> bufferServerToClient;
|
||||
bufferServerToClient.resize(32768);
|
||||
|
||||
|
||||
loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &bufferServerToClient[0], bufferServerToClient.size());
|
||||
}
|
||||
|
||||
m_data->m_dynamicsWorld->stepSimulation(dtInSec);
|
||||
}
|
||||
}
|
||||
|
||||
void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
|
||||
{
|
||||
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
|
||||
|
||||
@@ -53,7 +53,8 @@ public:
|
||||
|
||||
void enableCommandLogging(bool enable, const char* fileName);
|
||||
void replayFromLogFile(const char* fileName);
|
||||
void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||
void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||
void stepSimulationRealTime(double dtInSec);
|
||||
void applyJointDamping(int bodyUniqueId);
|
||||
};
|
||||
|
||||
|
||||
@@ -9,11 +9,12 @@
|
||||
#include "PhysicsServerSharedMemory.h"
|
||||
|
||||
#include "SharedMemoryCommon.h"
|
||||
|
||||
#include "Bullet3Common/b3Matrix3x3.h"
|
||||
#include "../Utils/b3Clock.h"
|
||||
#include "../MultiThreading/b3ThreadSupportInterface.h"
|
||||
|
||||
|
||||
|
||||
void MotionThreadFunc(void* userPtr,void* lsMemory);
|
||||
void* MotionlsMemoryFunc();
|
||||
#define MAX_MOTION_NUM_THREADS 1
|
||||
@@ -80,13 +81,23 @@ b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
|
||||
struct MotionArgs
|
||||
{
|
||||
MotionArgs()
|
||||
:m_physicsServerPtr(0)
|
||||
:m_physicsServerPtr(0),
|
||||
m_isPicking(false),
|
||||
m_isDragging(false),
|
||||
m_isReleasing(false)
|
||||
{
|
||||
}
|
||||
b3CriticalSection* m_cs;
|
||||
|
||||
PhysicsServerSharedMemory* m_physicsServerPtr;
|
||||
b3AlignedObjectArray<b3Vector3> m_positions;
|
||||
|
||||
btVector3 m_pos;
|
||||
btQuaternion m_orn;
|
||||
bool m_isPicking;
|
||||
bool m_isDragging;
|
||||
bool m_isReleasing;
|
||||
|
||||
};
|
||||
|
||||
struct MotionThreadLocalStorage
|
||||
@@ -113,23 +124,58 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
|
||||
args->m_cs->setSharedParam(0,eMotionIsInitialized);
|
||||
args->m_cs->unlock();
|
||||
|
||||
|
||||
do
|
||||
{
|
||||
//todo(erwincoumans): do we want some sleep to reduce CPU resources in this thread?
|
||||
#if 0
|
||||
|
||||
double deltaTimeInSeconds = double(clock.getTimeMicroseconds())/1000000.;
|
||||
if (deltaTimeInSeconds<(1./260.))
|
||||
if (deltaTimeInSeconds<(1./5000.))
|
||||
{
|
||||
skip++;
|
||||
if (deltaTimeInSeconds<.001)
|
||||
continue;
|
||||
} else
|
||||
{
|
||||
//process special controller commands, such as
|
||||
//VR controller button press/release and controller motion
|
||||
|
||||
btVector3 from = args->m_pos;
|
||||
btMatrix3x3 mat(args->m_orn);
|
||||
|
||||
btVector3 toX = args->m_pos+mat.getColumn(0);
|
||||
btVector3 toY = args->m_pos+mat.getColumn(1);
|
||||
btVector3 toZ = args->m_pos+mat.getColumn(2)*50.;
|
||||
|
||||
|
||||
if (args->m_isPicking)
|
||||
{
|
||||
args->m_isPicking = false;
|
||||
args->m_isDragging = true;
|
||||
args->m_physicsServerPtr->pickBody(from,-toZ);
|
||||
//printf("PICK!\n");
|
||||
}
|
||||
|
||||
if (args->m_isDragging)
|
||||
{
|
||||
args->m_physicsServerPtr->movePickedBody(from,-toZ);
|
||||
// printf(".");
|
||||
}
|
||||
|
||||
if (args->m_isReleasing)
|
||||
{
|
||||
args->m_isDragging = false;
|
||||
args->m_isReleasing = false;
|
||||
args->m_physicsServerPtr->removePickingConstraint();
|
||||
//printf("Release pick\n");
|
||||
}
|
||||
|
||||
//don't simulate over a huge timestep if we had some interruption (debugger breakpoint etc)
|
||||
btClamp(deltaTimeInSeconds,0.,0.1);
|
||||
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds);
|
||||
clock.reset();
|
||||
}
|
||||
|
||||
clock.reset();
|
||||
#endif
|
||||
args->m_physicsServerPtr->processClientCommands();
|
||||
|
||||
|
||||
} while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);
|
||||
} else
|
||||
{
|
||||
@@ -375,7 +421,7 @@ class PhysicsServerExample : public SharedMemoryCommon
|
||||
btClock m_clock;
|
||||
bool m_replay;
|
||||
int m_options;
|
||||
|
||||
|
||||
public:
|
||||
|
||||
PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0);
|
||||
@@ -417,6 +463,9 @@ public:
|
||||
|
||||
btVector3 getRayTo(int x,int y);
|
||||
|
||||
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]);
|
||||
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]);
|
||||
|
||||
virtual bool mouseMoveCallback(float x,float y)
|
||||
{
|
||||
if (m_replay)
|
||||
@@ -720,6 +769,28 @@ void PhysicsServerExample::renderScene()
|
||||
//m_args[0].m_cs->lock();
|
||||
|
||||
m_physicsServer.renderScene();
|
||||
|
||||
if (m_args[0].m_isPicking || m_args[0].m_isDragging)
|
||||
{
|
||||
btVector3 from = m_args[0].m_pos;
|
||||
btMatrix3x3 mat(m_args[0].m_orn);
|
||||
|
||||
btVector3 toX = m_args[0].m_pos+mat.getColumn(0);
|
||||
btVector3 toY = m_args[0].m_pos+mat.getColumn(1);
|
||||
btVector3 toZ = m_args[0].m_pos+mat.getColumn(2);
|
||||
|
||||
int width = 2;
|
||||
|
||||
|
||||
btVector4 color;
|
||||
color=btVector4(1,0,0,1);
|
||||
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toX,color,width);
|
||||
color=btVector4(0,1,0,1);
|
||||
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toY,color,width);
|
||||
color=btVector4(0,0,1,1);
|
||||
m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toZ,color,width);
|
||||
|
||||
}
|
||||
|
||||
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
|
||||
{
|
||||
@@ -856,4 +927,17 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt
|
||||
|
||||
}
|
||||
|
||||
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)
|
||||
void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4])
|
||||
{
|
||||
m_args[0].m_isPicking = (state!=0);
|
||||
m_args[0].m_isReleasing = (state==0);
|
||||
m_args[0].m_pos.setValue(pos[0],pos[1],pos[2]);
|
||||
m_args[0].m_orn.setValue(orn[0],orn[1],orn[2],orn[3]);
|
||||
}
|
||||
|
||||
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4])
|
||||
{
|
||||
m_args[0].m_pos.setValue(pos[0],pos[1],pos[2]);
|
||||
m_args[0].m_orn.setValue(orn[0],orn[1],orn[2],orn[3]);
|
||||
}
|
||||
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)
|
||||
|
||||
@@ -236,8 +236,10 @@ void PhysicsServerSharedMemory::releaseSharedMemory()
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec)
|
||||
{
|
||||
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec);
|
||||
}
|
||||
|
||||
|
||||
void PhysicsServerSharedMemory::processClientCommands()
|
||||
|
||||
@@ -26,6 +26,8 @@ public:
|
||||
|
||||
virtual void processClientCommands();
|
||||
|
||||
virtual void stepSimulationRealTime(double dtInSec);
|
||||
|
||||
//bool supportsJointMotor(class btMultiBody* body, int linkIndex);
|
||||
|
||||
//@todo(erwincoumans) Should we have shared memory commands for picking objects?
|
||||
|
||||
@@ -215,6 +215,7 @@ enum EnumSimParamUpdateFlags
|
||||
SIM_PARAM_UPDATE_GRAVITY=2,
|
||||
SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS=4,
|
||||
SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8,
|
||||
SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16,
|
||||
};
|
||||
|
||||
///Controlling a robot involves sending the desired state to its joint motor controllers.
|
||||
@@ -225,6 +226,7 @@ struct SendPhysicsSimulationParameters
|
||||
double m_gravityAcceleration[3];
|
||||
int m_numSimulationSubSteps;
|
||||
int m_numSolverIterations;
|
||||
bool m_allowRealTimeSimulation;
|
||||
};
|
||||
|
||||
struct RequestActualStateArgs
|
||||
|
||||
Reference in New Issue
Block a user