2015-07-14 22:30:17 +00:00
|
|
|
|
|
|
|
|
2016-07-11 07:26:40 +00:00
|
|
|
//todo(erwincoumans): re-use the upcoming b3RobotSimAPI here
|
2015-07-14 22:30:17 +00:00
|
|
|
|
|
|
|
#include "PhysicsServerExample.h"
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
#ifdef B3_USE_MIDI
|
|
|
|
#include "RtMidi.h"
|
|
|
|
#endif//B3_USE_MIDI
|
2015-07-14 22:30:17 +00:00
|
|
|
|
2015-11-23 04:50:32 +00:00
|
|
|
#include "PhysicsServerSharedMemory.h"
|
2016-10-09 01:40:09 +00:00
|
|
|
#include "Bullet3Common/b3CommandLineArgs.h"
|
2015-07-14 22:30:17 +00:00
|
|
|
#include "SharedMemoryCommon.h"
|
2016-07-18 06:50:11 +00:00
|
|
|
#include "Bullet3Common/b3Matrix3x3.h"
|
2016-07-08 02:24:44 +00:00
|
|
|
#include "../Utils/b3Clock.h"
|
|
|
|
#include "../MultiThreading/b3ThreadSupportInterface.h"
|
2016-12-27 03:40:09 +00:00
|
|
|
#include "SharedMemoryPublic.h"
|
2016-10-14 22:06:09 +00:00
|
|
|
#ifdef BT_ENABLE_VR
|
|
|
|
#include "../RenderingExamples/TinyVRGui.h"
|
|
|
|
#endif//BT_ENABLE_VR
|
|
|
|
|
|
|
|
|
|
|
|
#include "../CommonInterfaces/CommonParameterInterface.h"
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2016-09-09 18:28:38 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2016-10-04 15:53:59 +00:00
|
|
|
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
|
2016-09-08 22:15:58 +00:00
|
|
|
extern btVector3 gLastPickPos;
|
2017-01-06 01:41:58 +00:00
|
|
|
|
|
|
|
btVector3 gVRTeleportPosLocal(0,0,0);
|
|
|
|
btQuaternion gVRTeleportOrnLocal(0,0,0,1);
|
|
|
|
|
|
|
|
extern btVector3 gVRTeleportPos1;
|
|
|
|
extern btQuaternion gVRTeleportOrn;
|
2016-12-03 01:44:00 +00:00
|
|
|
btScalar gVRTeleportRotZ = 0;
|
2017-01-06 01:41:58 +00:00
|
|
|
|
2016-09-20 19:37:13 +00:00
|
|
|
extern btVector3 gVRGripperPos;
|
|
|
|
extern btQuaternion gVRGripperOrn;
|
2016-09-23 02:48:26 +00:00
|
|
|
extern btVector3 gVRController2Pos;
|
|
|
|
extern btQuaternion gVRController2Orn;
|
2016-09-20 19:37:13 +00:00
|
|
|
extern btScalar gVRGripperAnalog;
|
2016-10-04 15:53:59 +00:00
|
|
|
extern btScalar gVRGripper2Analog;
|
|
|
|
extern bool gCloseToKuka;
|
2016-09-20 19:37:13 +00:00
|
|
|
extern bool gEnableRealTimeSimVR;
|
2016-10-23 14:14:50 +00:00
|
|
|
extern bool gCreateDefaultRobotAssets;
|
|
|
|
extern int gInternalSimFlags;
|
2016-09-22 15:50:28 +00:00
|
|
|
extern int gCreateObjectSimVR;
|
2016-11-30 01:08:47 +00:00
|
|
|
extern bool gResetSimulation;
|
2016-11-17 00:12:59 +00:00
|
|
|
extern int gEnableKukaControl;
|
|
|
|
int gGraspingController = -1;
|
2016-09-22 15:50:28 +00:00
|
|
|
extern btScalar simTimeScalingFactor;
|
2016-12-27 03:40:09 +00:00
|
|
|
bool gBatchUserDebugLines = true;
|
2016-09-09 21:30:37 +00:00
|
|
|
extern bool gVRGripperClosed;
|
|
|
|
|
2016-12-03 01:44:00 +00:00
|
|
|
const char* startFileNameVR = "0_VRDemoSettings.txt";
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
#include <vector>
|
|
|
|
|
2016-12-03 01:44:00 +00:00
|
|
|
static void loadCurrentSettingsVR(b3CommandLineArgs& args)
|
|
|
|
{
|
2017-01-16 06:26:11 +00:00
|
|
|
//int currentEntry = 0;
|
2016-12-03 01:44:00 +00:00
|
|
|
FILE* f = fopen(startFileNameVR, "r");
|
|
|
|
if (f)
|
|
|
|
{
|
|
|
|
char oneline[1024];
|
|
|
|
char* argv[] = { 0,&oneline[0] };
|
2017-01-16 06:26:11 +00:00
|
|
|
|
2016-12-03 01:44:00 +00:00
|
|
|
while (fgets(oneline, 1024, f) != NULL)
|
|
|
|
{
|
|
|
|
char *pos;
|
|
|
|
if ((pos = strchr(oneline, '\n')) != NULL)
|
|
|
|
*pos = '\0';
|
|
|
|
args.addArgs(2, argv);
|
|
|
|
}
|
|
|
|
fclose(f);
|
|
|
|
}
|
2017-01-16 06:26:11 +00:00
|
|
|
|
2016-12-03 01:44:00 +00:00
|
|
|
};
|
2017-01-16 06:26:11 +00:00
|
|
|
|
|
|
|
//remember the settings (you don't want to re-tune again and again...)
|
|
|
|
static void saveCurrentSettingsVR()
|
|
|
|
{
|
|
|
|
FILE* f = fopen(startFileNameVR, "w");
|
|
|
|
if (f)
|
|
|
|
{
|
2017-01-26 03:17:57 +00:00
|
|
|
fprintf(f, "--camPosX= %f\n", gVRTeleportPos1[0]);
|
|
|
|
fprintf(f, "--camPosY= %f\n", gVRTeleportPos1[1]);
|
|
|
|
fprintf(f, "--camPosZ= %f\n", gVRTeleportPos1[2]);
|
2017-01-16 06:26:11 +00:00
|
|
|
fprintf(f, "--camRotZ= %f\n", gVRTeleportRotZ);
|
|
|
|
fclose(f);
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
2017-01-26 03:17:57 +00:00
|
|
|
#if B3_USE_MIDI
|
|
|
|
|
2016-12-03 01:44:00 +00:00
|
|
|
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
static float getParamf(float rangeMin, float rangeMax, int midiVal)
|
|
|
|
{
|
|
|
|
float v = rangeMin + (rangeMax - rangeMin)* (float(midiVal / 127.));
|
|
|
|
return v;
|
|
|
|
}
|
|
|
|
void midiCallback(double deltatime, std::vector< unsigned char > *message, void *userData)
|
|
|
|
{
|
|
|
|
unsigned int nBytes = message->size();
|
|
|
|
for (unsigned int i = 0; i<nBytes; i++)
|
|
|
|
std::cout << "Byte " << i << " = " << (int)message->at(i) << ", ";
|
|
|
|
if (nBytes > 0)
|
|
|
|
std::cout << "stamp = " << deltatime << std::endl;
|
|
|
|
|
|
|
|
if (nBytes > 2)
|
|
|
|
{
|
|
|
|
|
|
|
|
if (message->at(0) == 176)
|
|
|
|
{
|
|
|
|
if (message->at(1) == 16)
|
|
|
|
{
|
2016-12-03 01:44:00 +00:00
|
|
|
gVRTeleportRotZ= getParamf(-3.1415, 3.1415, message->at(2));
|
2017-01-26 03:17:57 +00:00
|
|
|
gVRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
|
2016-12-03 01:44:00 +00:00
|
|
|
saveCurrentSettingsVR();
|
2017-01-06 01:41:58 +00:00
|
|
|
// b3Printf("gVRTeleportOrnLocal rotZ = %f\n", gVRTeleportRotZ);
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
if (message->at(1) == 32)
|
|
|
|
{
|
|
|
|
gCreateDefaultRobotAssets = 1;
|
|
|
|
}
|
|
|
|
|
|
|
|
for (int i = 0; i < 3; i++)
|
|
|
|
{
|
|
|
|
if (message->at(1) == i)
|
|
|
|
{
|
2017-01-26 03:17:57 +00:00
|
|
|
gVRTeleportPos1[i] = getParamf(-2, 2, message->at(2));
|
2016-12-03 01:44:00 +00:00
|
|
|
saveCurrentSettingsVR();
|
2017-01-06 01:41:58 +00:00
|
|
|
// b3Printf("gVRTeleportPos[%d] = %f\n", i,gVRTeleportPosLocal[i]);
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif //B3_USE_MIDI
|
2016-10-23 14:14:50 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
bool gDebugRenderToggle = false;
|
2016-07-08 02:24:44 +00:00
|
|
|
void MotionThreadFunc(void* userPtr,void* lsMemory);
|
|
|
|
void* MotionlsMemoryFunc();
|
|
|
|
#define MAX_MOTION_NUM_THREADS 1
|
|
|
|
enum
|
|
|
|
{
|
|
|
|
numCubesX = 20,
|
|
|
|
numCubesY = 20
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
enum TestExampleBrowserCommunicationEnums
|
|
|
|
{
|
|
|
|
eRequestTerminateMotion= 13,
|
|
|
|
eMotionIsUnInitialized,
|
|
|
|
eMotionIsInitialized,
|
|
|
|
eMotionInitializationFailed,
|
|
|
|
eMotionHasTerminated
|
|
|
|
};
|
|
|
|
|
|
|
|
enum MultiThreadedGUIHelperCommunicationEnums
|
|
|
|
{
|
|
|
|
eGUIHelperIdle= 13,
|
|
|
|
eGUIHelperRegisterTexture,
|
|
|
|
eGUIHelperRegisterGraphicsShape,
|
|
|
|
eGUIHelperRegisterGraphicsInstance,
|
|
|
|
eGUIHelperCreateCollisionShapeGraphicsObject,
|
|
|
|
eGUIHelperCreateCollisionObjectGraphicsObject,
|
2016-09-22 15:50:28 +00:00
|
|
|
eGUIHelperCreateRigidBodyGraphicsObject,
|
2016-07-08 02:24:44 +00:00
|
|
|
eGUIHelperRemoveAllGraphicsInstances,
|
2016-08-08 21:23:44 +00:00
|
|
|
eGUIHelperCopyCameraImageData,
|
2016-11-12 02:07:42 +00:00
|
|
|
eGUIHelperAutogenerateGraphicsObjects,
|
2016-11-20 23:38:42 +00:00
|
|
|
eGUIUserDebugAddText,
|
|
|
|
eGUIUserDebugAddLine,
|
2017-01-17 23:42:32 +00:00
|
|
|
eGUIUserDebugAddParameter,
|
2016-11-20 23:38:42 +00:00
|
|
|
eGUIUserDebugRemoveItem,
|
|
|
|
eGUIUserDebugRemoveAllItems,
|
2016-07-08 02:24:44 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
#include <stdio.h>
|
|
|
|
//#include "BulletMultiThreaded/PlatformDefinitions.h"
|
|
|
|
|
|
|
|
#ifndef _WIN32
|
|
|
|
#include "../MultiThreading/b3PosixThreadSupport.h"
|
|
|
|
|
|
|
|
b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
|
|
|
|
{
|
|
|
|
b3PosixThreadSupport::ThreadConstructionInfo constructionInfo("MotionThreads",
|
|
|
|
MotionThreadFunc,
|
|
|
|
MotionlsMemoryFunc,
|
|
|
|
numThreads);
|
|
|
|
b3ThreadSupportInterface* threadSupport = new b3PosixThreadSupport(constructionInfo);
|
|
|
|
|
|
|
|
return threadSupport;
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
#elif defined( _WIN32)
|
|
|
|
#include "../MultiThreading/b3Win32ThreadSupport.h"
|
|
|
|
|
|
|
|
b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
|
|
|
|
{
|
|
|
|
b3Win32ThreadSupport::Win32ThreadConstructionInfo threadConstructionInfo("MotionThreads",MotionThreadFunc,MotionlsMemoryFunc,numThreads);
|
|
|
|
b3Win32ThreadSupport* threadSupport = new b3Win32ThreadSupport(threadConstructionInfo);
|
|
|
|
return threadSupport;
|
|
|
|
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
enum MyMouseCommandType
|
|
|
|
{
|
|
|
|
MyMouseMove = 1,
|
|
|
|
MyMouseButtonDown,
|
|
|
|
MyMouseButtonUp
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
};
|
|
|
|
struct MyMouseCommand
|
|
|
|
{
|
|
|
|
btVector3 m_rayFrom;
|
|
|
|
btVector3 m_rayTo;
|
|
|
|
int m_type;
|
|
|
|
};
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
struct MotionArgs
|
|
|
|
{
|
|
|
|
MotionArgs()
|
2016-09-08 22:15:58 +00:00
|
|
|
:m_physicsServerPtr(0)
|
2016-07-08 02:24:44 +00:00
|
|
|
{
|
2016-09-08 22:15:58 +00:00
|
|
|
for (int i=0;i<MAX_VR_CONTROLLERS;i++)
|
|
|
|
{
|
2016-12-27 03:40:09 +00:00
|
|
|
m_vrControllerEvents[i].m_numButtonEvents = 0;
|
|
|
|
m_vrControllerEvents[i].m_numMoveEvents = 0;
|
|
|
|
for (int b=0;b<MAX_VR_BUTTONS;b++)
|
|
|
|
{
|
|
|
|
m_vrControllerEvents[i].m_buttons[b]=0;
|
|
|
|
}
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
m_isVrControllerPicking[i] = false;
|
|
|
|
m_isVrControllerDragging[i] = false;
|
|
|
|
m_isVrControllerReleasing[i] = false;
|
|
|
|
m_isVrControllerTeleporting[i] = false;
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
b3CriticalSection* m_cs;
|
2016-12-29 05:51:54 +00:00
|
|
|
b3CriticalSection* m_cs2;
|
|
|
|
b3CriticalSection* m_cs3;
|
|
|
|
b3CriticalSection* m_csGUI;
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
btAlignedObjectArray<MyMouseCommand> m_mouseCommands;
|
2016-12-27 03:40:09 +00:00
|
|
|
|
|
|
|
b3VRControllerEvent m_vrControllerEvents[MAX_VR_CONTROLLERS];
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
b3VRControllerEvent m_sendVrControllerEvents[MAX_VR_CONTROLLERS];
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
PhysicsServerSharedMemory* m_physicsServerPtr;
|
|
|
|
b3AlignedObjectArray<b3Vector3> m_positions;
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
btVector3 m_vrControllerPos[MAX_VR_CONTROLLERS];
|
|
|
|
btQuaternion m_vrControllerOrn[MAX_VR_CONTROLLERS];
|
|
|
|
bool m_isVrControllerPicking[MAX_VR_CONTROLLERS];
|
|
|
|
bool m_isVrControllerDragging[MAX_VR_CONTROLLERS];
|
|
|
|
bool m_isVrControllerReleasing[MAX_VR_CONTROLLERS];
|
|
|
|
bool m_isVrControllerTeleporting[MAX_VR_CONTROLLERS];
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
struct MotionThreadLocalStorage
|
|
|
|
{
|
|
|
|
int threadId;
|
|
|
|
};
|
|
|
|
|
2017-01-08 20:49:04 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
float clampedDeltaTime = 0.2;
|
2017-01-08 21:06:08 +00:00
|
|
|
float sleepTimeThreshold = 8./1000.;
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2017-01-08 20:49:04 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
void MotionThreadFunc(void* userPtr,void* lsMemory)
|
|
|
|
{
|
2016-07-09 22:09:09 +00:00
|
|
|
printf("MotionThreadFunc thread started\n");
|
2017-01-16 06:26:11 +00:00
|
|
|
//MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory;
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
MotionArgs* args = (MotionArgs*) userPtr;
|
2017-01-16 06:26:11 +00:00
|
|
|
//int workLeft = true;
|
2016-07-08 02:24:44 +00:00
|
|
|
b3Clock clock;
|
|
|
|
clock.reset();
|
|
|
|
bool init = true;
|
|
|
|
if (init)
|
|
|
|
{
|
|
|
|
|
|
|
|
args->m_cs->lock();
|
|
|
|
args->m_cs->setSharedParam(0,eMotionIsInitialized);
|
|
|
|
args->m_cs->unlock();
|
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
double deltaTimeInSeconds = 0;
|
2016-07-08 02:24:44 +00:00
|
|
|
do
|
|
|
|
{
|
2016-12-29 05:51:54 +00:00
|
|
|
BT_PROFILE("loop");
|
2017-01-08 20:49:04 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
{
|
2017-01-08 21:06:08 +00:00
|
|
|
BT_PROFILE("usleep(0)");
|
2017-01-08 20:49:04 +00:00
|
|
|
b3Clock::usleep(0);
|
|
|
|
}
|
|
|
|
double dt = double(clock.getTimeMicroseconds())/1000000.;
|
2017-01-30 04:59:47 +00:00
|
|
|
clock.reset();
|
2017-01-08 20:49:04 +00:00
|
|
|
deltaTimeInSeconds+= dt;
|
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
{
|
2016-08-13 19:21:18 +00:00
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
//process special controller commands, such as
|
|
|
|
//VR controller button press/release and controller motion
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
for (int c=0;c<MAX_VR_CONTROLLERS;c++)
|
2016-07-18 06:50:11 +00:00
|
|
|
{
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
btVector3 from = args->m_vrControllerPos[c];
|
|
|
|
btMatrix3x3 mat(args->m_vrControllerOrn[c]);
|
|
|
|
|
|
|
|
btScalar pickDistance = 1000.;
|
2016-11-17 00:12:59 +00:00
|
|
|
btVector3 to = from+mat.getColumn(0)*pickDistance;
|
|
|
|
// btVector3 toY = from+mat.getColumn(1)*pickDistance;
|
|
|
|
// btVector3 toZ = from+mat.getColumn(2)*pickDistance;
|
2016-09-08 22:15:58 +00:00
|
|
|
|
|
|
|
if (args->m_isVrControllerTeleporting[c])
|
|
|
|
{
|
|
|
|
args->m_isVrControllerTeleporting[c] = false;
|
2016-11-17 00:12:59 +00:00
|
|
|
args->m_physicsServerPtr->pickBody(from, to);
|
2016-09-08 22:15:58 +00:00
|
|
|
args->m_physicsServerPtr->removePickingConstraint();
|
|
|
|
}
|
|
|
|
|
2016-11-30 01:08:47 +00:00
|
|
|
// if (!gEnableKukaControl)
|
2016-09-08 22:15:58 +00:00
|
|
|
{
|
2016-10-04 15:53:59 +00:00
|
|
|
if (args->m_isVrControllerPicking[c])
|
|
|
|
{
|
|
|
|
args->m_isVrControllerPicking[c] = false;
|
|
|
|
args->m_isVrControllerDragging[c] = true;
|
2016-11-17 00:12:59 +00:00
|
|
|
args->m_physicsServerPtr->pickBody(from, to);
|
2016-10-04 15:53:59 +00:00
|
|
|
//printf("PICK!\n");
|
|
|
|
}
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
if (args->m_isVrControllerDragging[c])
|
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
args->m_physicsServerPtr->movePickedBody(from, to);
|
2016-09-08 22:15:58 +00:00
|
|
|
// printf(".");
|
|
|
|
}
|
|
|
|
|
|
|
|
if (args->m_isVrControllerReleasing[c])
|
|
|
|
{
|
|
|
|
args->m_isVrControllerDragging[c] = false;
|
|
|
|
args->m_isVrControllerReleasing[c] = false;
|
|
|
|
args->m_physicsServerPtr->removePickingConstraint();
|
|
|
|
//printf("Release pick\n");
|
|
|
|
}
|
2016-07-18 06:50:11 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
//don't simulate over a huge timestep if we had some interruption (debugger breakpoint etc)
|
2016-09-08 22:15:58 +00:00
|
|
|
if (deltaTimeInSeconds>clampedDeltaTime)
|
|
|
|
{
|
|
|
|
deltaTimeInSeconds = clampedDeltaTime;
|
2016-12-23 23:20:04 +00:00
|
|
|
//b3Warning("Clamp deltaTime from %f to %f",deltaTimeInSeconds, clampedDeltaTime);
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
args->m_csGUI->lock();
|
2016-12-27 03:40:09 +00:00
|
|
|
|
|
|
|
int numSendVrControllers = 0;
|
|
|
|
for (int i=0;i<MAX_VR_CONTROLLERS;i++)
|
|
|
|
{
|
|
|
|
if (args->m_vrControllerEvents[i].m_numButtonEvents+args->m_vrControllerEvents[i].m_numMoveEvents)
|
|
|
|
{
|
|
|
|
args->m_sendVrControllerEvents[numSendVrControllers++] =
|
|
|
|
args->m_vrControllerEvents[i];
|
|
|
|
|
|
|
|
|
|
|
|
if (args->m_vrControllerEvents[i].m_numButtonEvents)
|
|
|
|
{
|
|
|
|
for (int b=0;b<MAX_VR_BUTTONS;b++)
|
|
|
|
{
|
|
|
|
args->m_vrControllerEvents[i].m_buttons[b] &= eButtonIsDown;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
args->m_vrControllerEvents[i].m_numMoveEvents = 0;
|
|
|
|
args->m_vrControllerEvents[i].m_numButtonEvents = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
args->m_csGUI->unlock();
|
|
|
|
{
|
|
|
|
BT_PROFILE("stepSimulationRealTime");
|
|
|
|
args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers);
|
|
|
|
}
|
2016-09-08 22:15:58 +00:00
|
|
|
deltaTimeInSeconds = 0;
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
args->m_csGUI->lock();
|
2016-11-17 00:12:59 +00:00
|
|
|
for (int i = 0; i < args->m_mouseCommands.size(); i++)
|
|
|
|
{
|
|
|
|
switch (args->m_mouseCommands[i].m_type)
|
|
|
|
{
|
|
|
|
case MyMouseMove:
|
|
|
|
{
|
|
|
|
args->m_physicsServerPtr->movePickedBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
|
|
|
|
break;
|
|
|
|
};
|
|
|
|
case MyMouseButtonDown:
|
|
|
|
{
|
|
|
|
args->m_physicsServerPtr->pickBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
case MyMouseButtonUp:
|
|
|
|
{
|
|
|
|
args->m_physicsServerPtr->removePickingConstraint();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
default:
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
}
|
|
|
|
args->m_mouseCommands.clear();
|
2016-12-29 05:51:54 +00:00
|
|
|
args->m_csGUI->unlock();
|
2016-11-17 00:12:59 +00:00
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
{
|
|
|
|
BT_PROFILE("processClientCommands");
|
|
|
|
args->m_physicsServerPtr->processClientCommands();
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
} while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
args->m_cs->lock();
|
|
|
|
args->m_cs->setSharedParam(0,eMotionInitializationFailed);
|
|
|
|
args->m_cs->unlock();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//do nothing
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void* MotionlsMemoryFunc()
|
|
|
|
{
|
|
|
|
//don't create local store memory, just return 0
|
|
|
|
return new MotionThreadLocalStorage;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2016-11-14 15:39:34 +00:00
|
|
|
struct UserDebugDrawLine
|
|
|
|
{
|
|
|
|
double m_debugLineFromXYZ[3];
|
|
|
|
double m_debugLineToXYZ[3];
|
|
|
|
double m_debugLineColorRGB[3];
|
|
|
|
double m_lineWidth;
|
|
|
|
|
|
|
|
double m_lifeTime;
|
|
|
|
int m_itemUniqueId;
|
|
|
|
};
|
|
|
|
|
2017-01-17 23:42:32 +00:00
|
|
|
struct UserDebugParameter
|
|
|
|
{
|
|
|
|
char m_text[1024];
|
|
|
|
double m_rangeMin;
|
|
|
|
double m_rangeMax;
|
2017-01-18 01:38:30 +00:00
|
|
|
btScalar m_value;
|
2017-01-17 23:42:32 +00:00
|
|
|
int m_itemUniqueId;
|
|
|
|
};
|
|
|
|
|
2016-11-14 15:39:34 +00:00
|
|
|
struct UserDebugText
|
|
|
|
{
|
|
|
|
char m_text[1024];
|
|
|
|
double m_textPositionXYZ[3];
|
|
|
|
double m_textColorRGB[3];
|
|
|
|
double textSize;
|
|
|
|
|
|
|
|
double m_lifeTime;
|
|
|
|
int m_itemUniqueId;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
|
|
|
|
{
|
2017-01-16 06:26:11 +00:00
|
|
|
// CommonGraphicsApp* m_app;
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
b3CriticalSection* m_cs;
|
2016-12-29 05:51:54 +00:00
|
|
|
b3CriticalSection* m_cs2;
|
|
|
|
b3CriticalSection* m_cs3;
|
|
|
|
b3CriticalSection* m_csGUI;
|
2016-11-17 00:12:59 +00:00
|
|
|
|
2016-11-14 15:39:34 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
public:
|
|
|
|
|
|
|
|
GUIHelperInterface* m_childGuiHelper;
|
|
|
|
|
2016-11-14 15:39:34 +00:00
|
|
|
int m_uidGenerator;
|
2016-07-08 02:24:44 +00:00
|
|
|
const unsigned char* m_texels;
|
|
|
|
int m_textureWidth;
|
|
|
|
int m_textureHeight;
|
|
|
|
|
|
|
|
|
|
|
|
int m_shapeIndex;
|
|
|
|
const float* m_position;
|
|
|
|
const float* m_quaternion;
|
|
|
|
const float* m_color;
|
|
|
|
const float* m_scaling;
|
|
|
|
|
|
|
|
const float* m_vertices;
|
|
|
|
int m_numvertices;
|
|
|
|
const int* m_indices;
|
|
|
|
int m_numIndices;
|
|
|
|
int m_primitiveType;
|
|
|
|
int m_textureId;
|
|
|
|
int m_instanceId;
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
void mainThreadRelease()
|
|
|
|
{
|
|
|
|
BT_PROFILE("mainThreadRelease");
|
|
|
|
|
|
|
|
getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
|
|
|
|
getCriticalSection3()->lock();
|
|
|
|
getCriticalSection2()->unlock();
|
|
|
|
getCriticalSection()->lock();
|
|
|
|
getCriticalSection2()->lock();
|
|
|
|
getCriticalSection()->unlock();
|
|
|
|
getCriticalSection3()->unlock();
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
void workerThreadWait()
|
|
|
|
{
|
|
|
|
BT_PROFILE("workerThreadWait");
|
|
|
|
m_cs2->lock();
|
|
|
|
m_cs->unlock();
|
|
|
|
m_cs2->unlock();
|
|
|
|
m_cs3->lock();
|
|
|
|
m_cs3->unlock();
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
|
|
|
|
{
|
|
|
|
b3Clock::usleep(100);
|
|
|
|
}
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
|
2017-01-16 06:26:11 +00:00
|
|
|
:
|
|
|
|
//m_app(app),
|
|
|
|
m_cs(0),
|
2016-12-29 05:51:54 +00:00
|
|
|
m_cs2(0),
|
|
|
|
m_cs3(0),
|
|
|
|
m_csGUI(0),
|
2016-11-14 15:39:34 +00:00
|
|
|
m_uidGenerator(0),
|
2016-07-08 02:24:44 +00:00
|
|
|
m_texels(0),
|
|
|
|
m_textureId(-1)
|
|
|
|
{
|
|
|
|
m_childGuiHelper = guiHelper;;
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual ~MultiThreadedOpenGLGuiHelper()
|
|
|
|
{
|
2017-01-10 22:57:16 +00:00
|
|
|
//delete m_childGuiHelper;
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
void setCriticalSection(b3CriticalSection* cs)
|
|
|
|
{
|
|
|
|
m_cs = cs;
|
|
|
|
}
|
|
|
|
|
|
|
|
b3CriticalSection* getCriticalSection()
|
|
|
|
{
|
|
|
|
return m_cs;
|
|
|
|
}
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
|
|
|
|
void setCriticalSection2(b3CriticalSection* cs)
|
|
|
|
{
|
|
|
|
m_cs2 = cs;
|
|
|
|
}
|
|
|
|
|
|
|
|
b3CriticalSection* getCriticalSection2()
|
|
|
|
{
|
|
|
|
return m_cs2;
|
|
|
|
}
|
|
|
|
|
|
|
|
void setCriticalSection3(b3CriticalSection* cs)
|
|
|
|
{
|
|
|
|
m_cs3 = cs;
|
|
|
|
}
|
|
|
|
|
|
|
|
void setCriticalSectionGUI(b3CriticalSection* cs)
|
|
|
|
{
|
|
|
|
m_csGUI = cs;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
b3CriticalSection* getCriticalSection3()
|
|
|
|
{
|
|
|
|
return m_cs3;
|
|
|
|
}
|
2016-09-22 15:50:28 +00:00
|
|
|
btRigidBody* m_body;
|
|
|
|
btVector3 m_color3;
|
|
|
|
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color)
|
|
|
|
{
|
|
|
|
m_body = body;
|
|
|
|
m_color3 = color;
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperCreateRigidBodyGraphicsObject);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
|
|
|
|
2016-09-22 15:50:28 +00:00
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
btCollisionObject* m_obj;
|
|
|
|
btVector3 m_color2;
|
|
|
|
|
|
|
|
virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj,const btVector3& color)
|
|
|
|
{
|
|
|
|
m_obj = obj;
|
|
|
|
m_color2 = color;
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperCreateCollisionObjectGraphicsObject);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
btCollisionShape* m_colShape;
|
|
|
|
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
|
|
|
|
{
|
|
|
|
m_colShape = collisionShape;
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperCreateCollisionShapeGraphicsObject);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld)
|
|
|
|
{
|
|
|
|
//this check is to prevent a crash, in case we removed all graphics instances, but there are still physics objects.
|
|
|
|
//the check will be obsolete, once we have a better/safer way of synchronizing physics->graphics transforms
|
2016-12-29 05:51:54 +00:00
|
|
|
if ( m_childGuiHelper->getRenderInterface() && m_childGuiHelper->getRenderInterface()->getTotalNumInstances()>0)
|
2016-07-08 02:24:44 +00:00
|
|
|
{
|
|
|
|
m_childGuiHelper->syncPhysicsToGraphics(rbWorld);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual void render(const btDiscreteDynamicsWorld* rbWorld)
|
|
|
|
{
|
|
|
|
m_childGuiHelper->render(0);
|
|
|
|
}
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld)
|
|
|
|
{
|
|
|
|
m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
virtual int registerTexture(const unsigned char* texels, int width, int height)
|
|
|
|
{
|
|
|
|
m_texels = texels;
|
|
|
|
m_textureWidth = width;
|
|
|
|
m_textureHeight = height;
|
|
|
|
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperRegisterTexture);
|
2016-12-29 05:51:54 +00:00
|
|
|
|
|
|
|
workerThreadWait();
|
|
|
|
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
return m_textureId;
|
|
|
|
}
|
|
|
|
virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
|
|
|
|
{
|
|
|
|
m_vertices = vertices;
|
|
|
|
m_numvertices = numvertices;
|
|
|
|
m_indices = indices;
|
|
|
|
m_numIndices = numIndices;
|
|
|
|
m_primitiveType = primitiveType;
|
|
|
|
m_textureId = textureId;
|
|
|
|
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperRegisterGraphicsShape);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
return m_shapeIndex;
|
|
|
|
}
|
|
|
|
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
|
|
|
|
{
|
|
|
|
m_shapeIndex = shapeIndex;
|
|
|
|
m_position = position;
|
|
|
|
m_quaternion = quaternion;
|
|
|
|
m_color = color;
|
|
|
|
m_scaling = scaling;
|
|
|
|
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperRegisterGraphicsInstance);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-07-08 02:24:44 +00:00
|
|
|
return m_instanceId;
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual void removeAllGraphicsInstances()
|
|
|
|
{
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperRemoveAllGraphicsInstances);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
virtual Common2dCanvasInterface* get2dCanvasInterface()
|
|
|
|
{
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual CommonParameterInterface* getParameterInterface()
|
|
|
|
{
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual CommonRenderInterface* getRenderInterface()
|
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
return m_childGuiHelper->getRenderInterface();
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
virtual CommonGraphicsApp* getAppInterface()
|
|
|
|
{
|
2016-07-09 22:09:09 +00:00
|
|
|
return m_childGuiHelper->getAppInterface();
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
virtual void setUpAxis(int axis)
|
|
|
|
{
|
|
|
|
m_childGuiHelper->setUpAxis(axis);
|
|
|
|
}
|
|
|
|
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
|
|
|
|
{
|
2016-08-11 18:20:31 +00:00
|
|
|
m_childGuiHelper->resetCamera(camDist,pitch,yaw,camPosX,camPosY,camPosZ);
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
2016-08-08 21:23:44 +00:00
|
|
|
float m_viewMatrix[16];
|
|
|
|
float m_projectionMatrix[16];
|
|
|
|
unsigned char* m_pixelsRGBA;
|
|
|
|
int m_rgbaBufferSizeInPixels;
|
|
|
|
float* m_depthBuffer;
|
|
|
|
int m_depthBufferSizeInPixels;
|
2016-08-11 21:55:30 +00:00
|
|
|
int* m_segmentationMaskBuffer;
|
|
|
|
int m_segmentationMaskBufferSizeInPixels;
|
2016-08-08 21:23:44 +00:00
|
|
|
int m_startPixelIndex;
|
|
|
|
int m_destinationWidth;
|
|
|
|
int m_destinationHeight;
|
|
|
|
int* m_numPixelsCopied;
|
|
|
|
|
2016-08-11 21:55:30 +00:00
|
|
|
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
|
|
|
|
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
|
|
|
float* depthBuffer, int depthBufferSizeInPixels,
|
|
|
|
int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels,
|
|
|
|
int startPixelIndex, int destinationWidth,
|
|
|
|
int destinationHeight, int* numPixelsCopied)
|
2016-07-08 02:24:44 +00:00
|
|
|
{
|
2016-08-08 21:23:44 +00:00
|
|
|
m_cs->lock();
|
|
|
|
for (int i=0;i<16;i++)
|
|
|
|
{
|
|
|
|
m_viewMatrix[i] = viewMatrix[i];
|
|
|
|
m_projectionMatrix[i] = projectionMatrix[i];
|
|
|
|
}
|
|
|
|
m_pixelsRGBA = pixelsRGBA;
|
|
|
|
m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
|
|
|
|
m_depthBuffer = depthBuffer;
|
|
|
|
m_depthBufferSizeInPixels = depthBufferSizeInPixels;
|
2016-08-11 21:55:30 +00:00
|
|
|
m_segmentationMaskBuffer = segmentationMaskBuffer;
|
|
|
|
m_segmentationMaskBufferSizeInPixels = segmentationMaskBufferSizeInPixels;
|
2016-08-08 21:23:44 +00:00
|
|
|
m_startPixelIndex = startPixelIndex;
|
|
|
|
m_destinationWidth = destinationWidth;
|
|
|
|
m_destinationHeight = destinationHeight;
|
|
|
|
m_numPixelsCopied = numPixelsCopied;
|
|
|
|
|
|
|
|
m_cs->setSharedParam(1,eGUIHelperCopyCameraImageData);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
2016-08-08 21:23:44 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2016-11-12 02:07:42 +00:00
|
|
|
btDiscreteDynamicsWorld* m_dynamicsWorld;
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
|
|
|
|
{
|
2016-11-12 02:07:42 +00:00
|
|
|
m_dynamicsWorld = rbWorld;
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1, eGUIHelperAutogenerateGraphicsObjects);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)
|
|
|
|
{
|
|
|
|
}
|
2016-11-14 15:39:34 +00:00
|
|
|
|
|
|
|
|
|
|
|
btAlignedObjectArray<UserDebugText> m_userDebugText;
|
|
|
|
|
|
|
|
UserDebugText m_tmpText;
|
|
|
|
|
|
|
|
virtual int addUserDebugText3D( const char* txt, const double positionXYZ[3], const double textColorRGB[3], double size, double lifeTime)
|
|
|
|
{
|
|
|
|
|
|
|
|
m_tmpText.m_itemUniqueId = m_uidGenerator++;
|
|
|
|
m_tmpText.m_lifeTime = lifeTime;
|
|
|
|
m_tmpText.textSize = size;
|
2017-01-16 06:26:11 +00:00
|
|
|
//int len = strlen(txt);
|
2016-11-14 15:39:34 +00:00
|
|
|
strcpy(m_tmpText.m_text,txt);
|
|
|
|
m_tmpText.m_textPositionXYZ[0] = positionXYZ[0];
|
|
|
|
m_tmpText.m_textPositionXYZ[1] = positionXYZ[1];
|
|
|
|
m_tmpText.m_textPositionXYZ[2] = positionXYZ[2];
|
|
|
|
m_tmpText.m_textColorRGB[0] = textColorRGB[0];
|
|
|
|
m_tmpText.m_textColorRGB[1] = textColorRGB[1];
|
|
|
|
m_tmpText.m_textColorRGB[2] = textColorRGB[2];
|
|
|
|
|
|
|
|
m_cs->lock();
|
2016-11-20 23:38:42 +00:00
|
|
|
m_cs->setSharedParam(1, eGUIUserDebugAddText);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-11-14 15:39:34 +00:00
|
|
|
|
|
|
|
return m_userDebugText[m_userDebugText.size()-1].m_itemUniqueId;
|
|
|
|
}
|
|
|
|
|
2017-01-17 23:42:32 +00:00
|
|
|
btAlignedObjectArray<UserDebugParameter*> m_userDebugParams;
|
|
|
|
UserDebugParameter m_tmpParam;
|
|
|
|
|
|
|
|
virtual int readUserDebugParameter(int itemUniqueId, double* value)
|
|
|
|
{
|
|
|
|
for (int i=0;i<m_userDebugParams.size();i++)
|
|
|
|
{
|
|
|
|
if (m_userDebugParams[i]->m_itemUniqueId == itemUniqueId)
|
|
|
|
{
|
|
|
|
*value = m_userDebugParams[i]->m_value;
|
|
|
|
return 1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue)
|
|
|
|
{
|
|
|
|
strcpy(m_tmpParam.m_text,txt);
|
|
|
|
m_tmpParam.m_rangeMin = rangeMin;
|
|
|
|
m_tmpParam.m_rangeMax = rangeMax;
|
|
|
|
m_tmpParam.m_value = startValue;
|
|
|
|
m_tmpParam.m_itemUniqueId = m_uidGenerator++;
|
|
|
|
|
|
|
|
m_cs->lock();
|
|
|
|
m_cs->setSharedParam(1, eGUIUserDebugAddParameter);
|
|
|
|
workerThreadWait();
|
|
|
|
|
|
|
|
return (*m_userDebugParams[m_userDebugParams.size()-1]).m_itemUniqueId;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-11-14 15:39:34 +00:00
|
|
|
btAlignedObjectArray<UserDebugDrawLine> m_userDebugLines;
|
2016-11-20 23:38:42 +00:00
|
|
|
UserDebugDrawLine m_tmpLine;
|
2016-11-14 15:39:34 +00:00
|
|
|
|
|
|
|
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime )
|
|
|
|
{
|
2016-11-20 23:38:42 +00:00
|
|
|
m_tmpLine.m_lifeTime = lifeTime;
|
|
|
|
m_tmpLine.m_lineWidth = lineWidth;
|
|
|
|
m_tmpLine.m_itemUniqueId = m_uidGenerator++;
|
|
|
|
m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0];
|
|
|
|
m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1];
|
|
|
|
m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2];
|
|
|
|
|
|
|
|
m_tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0];
|
|
|
|
m_tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1];
|
|
|
|
m_tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2];
|
2016-11-14 15:39:34 +00:00
|
|
|
|
2016-11-20 23:38:42 +00:00
|
|
|
m_tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0];
|
|
|
|
m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1];
|
|
|
|
m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2];
|
2016-11-14 15:39:34 +00:00
|
|
|
|
|
|
|
m_cs->lock();
|
2016-11-20 23:38:42 +00:00
|
|
|
m_cs->setSharedParam(1, eGUIUserDebugAddLine);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-11-14 15:39:34 +00:00
|
|
|
return m_userDebugLines[m_userDebugLines.size()-1].m_itemUniqueId;
|
|
|
|
}
|
|
|
|
|
|
|
|
int m_removeDebugItemUid;
|
|
|
|
|
|
|
|
virtual void removeUserDebugItem( int debugItemUniqueId)
|
|
|
|
{
|
|
|
|
m_removeDebugItemUid = debugItemUniqueId;
|
|
|
|
m_cs->lock();
|
2016-11-20 23:38:42 +00:00
|
|
|
m_cs->setSharedParam(1, eGUIUserDebugRemoveItem);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-11-20 01:13:56 +00:00
|
|
|
|
2016-11-14 15:39:34 +00:00
|
|
|
}
|
|
|
|
virtual void removeAllUserDebugItems( )
|
|
|
|
{
|
|
|
|
m_cs->lock();
|
2016-11-20 23:38:42 +00:00
|
|
|
m_cs->setSharedParam(1, eGUIUserDebugRemoveAllItems);
|
2016-12-29 05:51:54 +00:00
|
|
|
workerThreadWait();
|
2016-11-14 15:39:34 +00:00
|
|
|
|
|
|
|
}
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
|
|
|
|
class PhysicsServerExample : public SharedMemoryCommon
|
|
|
|
{
|
|
|
|
PhysicsServerSharedMemory m_physicsServer;
|
2016-07-08 02:24:44 +00:00
|
|
|
b3ThreadSupportInterface* m_threadSupport;
|
|
|
|
MotionArgs m_args[MAX_MOTION_NUM_THREADS];
|
|
|
|
MultiThreadedOpenGLGuiHelper* m_multiThreadedHelper;
|
2015-08-06 18:59:31 +00:00
|
|
|
bool m_wantsShutdown;
|
2016-11-17 00:12:59 +00:00
|
|
|
#ifdef B3_USE_MIDI
|
|
|
|
RtMidiIn* m_midi;
|
|
|
|
#endif
|
2015-08-06 18:59:31 +00:00
|
|
|
bool m_isConnected;
|
2015-09-03 21:18:22 +00:00
|
|
|
btClock m_clock;
|
2015-11-01 20:48:15 +00:00
|
|
|
bool m_replay;
|
2017-01-16 06:26:11 +00:00
|
|
|
// int m_options;
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-10-14 22:06:09 +00:00
|
|
|
#ifdef BT_ENABLE_VR
|
|
|
|
TinyVRGui* m_tinyVrGui;
|
|
|
|
#endif
|
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
public:
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0);
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
virtual ~PhysicsServerExample();
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
virtual void initPhysics();
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
virtual void stepSimulation(float deltaTime);
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-10-29 18:25:50 +00:00
|
|
|
void enableCommandLogging()
|
|
|
|
{
|
|
|
|
m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
|
|
|
|
}
|
2015-10-30 17:30:48 +00:00
|
|
|
|
|
|
|
void replayFromLogFile()
|
|
|
|
{
|
2015-11-01 20:48:15 +00:00
|
|
|
m_replay = true;
|
2015-10-30 17:30:48 +00:00
|
|
|
m_physicsServer.replayFromLogFile("BulletPhysicsCommandLog.bin");
|
|
|
|
}
|
|
|
|
|
2016-05-18 23:21:40 +00:00
|
|
|
|
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
virtual void resetCamera()
|
|
|
|
{
|
|
|
|
float dist = 5;
|
|
|
|
float pitch = 50;
|
|
|
|
float yaw = 35;
|
|
|
|
float targetPos[3]={0,0,0};//-3,2.8,-2.5};
|
|
|
|
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
|
|
|
}
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
virtual bool wantsTermination();
|
2015-08-06 18:59:31 +00:00
|
|
|
virtual bool isConnected();
|
2015-08-07 07:13:26 +00:00
|
|
|
virtual void renderScene();
|
2016-11-20 01:13:56 +00:00
|
|
|
void drawUserDebugLines();
|
2016-07-08 02:24:44 +00:00
|
|
|
virtual void exitPhysics();
|
2015-08-07 07:13:26 +00:00
|
|
|
|
|
|
|
virtual void physicsDebugDraw(int debugFlags);
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
btVector3 getRayTo(int x,int y);
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]);
|
2016-09-15 23:57:00 +00:00
|
|
|
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis);
|
2016-10-23 14:14:50 +00:00
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
virtual bool mouseMoveCallback(float x,float y)
|
|
|
|
{
|
2015-11-01 20:48:15 +00:00
|
|
|
if (m_replay)
|
|
|
|
return false;
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
CommonRenderInterface* renderer = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface();// m_guiHelper->getRenderInterface();
|
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
if (!renderer)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
btVector3 rayTo = getRayTo(int(x), int(y));
|
|
|
|
btVector3 rayFrom;
|
|
|
|
renderer->getActiveCamera()->getCameraPosition(rayFrom);
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
MyMouseCommand cmd;
|
|
|
|
cmd.m_rayFrom = rayFrom;
|
|
|
|
cmd.m_rayTo = rayTo;
|
|
|
|
cmd.m_type = MyMouseMove;
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->lock();
|
2016-11-17 00:12:59 +00:00
|
|
|
m_args[0].m_mouseCommands.push_back(cmd);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->unlock();
|
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
return false;
|
|
|
|
};
|
|
|
|
|
|
|
|
virtual bool mouseButtonCallback(int button, int state, float x, float y)
|
|
|
|
{
|
2015-11-01 20:48:15 +00:00
|
|
|
if (m_replay)
|
|
|
|
return false;
|
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
if (!renderer)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
|
|
|
|
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
if (state==1)
|
|
|
|
{
|
|
|
|
if(button==0 && (!window->isModifierKeyPressed(B3G_ALT) && !window->isModifierKeyPressed(B3G_CONTROL) ))
|
|
|
|
{
|
|
|
|
btVector3 camPos;
|
|
|
|
renderer->getActiveCamera()->getCameraPosition(camPos);
|
|
|
|
|
|
|
|
btVector3 rayFrom = camPos;
|
|
|
|
btVector3 rayTo = getRayTo(int(x),int(y));
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
MyMouseCommand cmd;
|
|
|
|
cmd.m_rayFrom = rayFrom;
|
|
|
|
cmd.m_rayTo = rayTo;
|
|
|
|
cmd.m_type = MyMouseButtonDown;
|
2016-12-29 05:51:54 +00:00
|
|
|
|
|
|
|
m_args[0].m_csGUI->lock();
|
2016-11-17 00:12:59 +00:00
|
|
|
m_args[0].m_mouseCommands.push_back(cmd);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->unlock();
|
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
|
|
|
|
}
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
if (button==0)
|
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
//m_physicsServer.removePickingConstraint();
|
|
|
|
MyMouseCommand cmd;
|
|
|
|
cmd.m_rayFrom.setValue(0,0,0);
|
|
|
|
cmd.m_rayTo.setValue(0, 0, 0);
|
|
|
|
cmd.m_type = MyMouseButtonUp;
|
2016-12-29 05:51:54 +00:00
|
|
|
|
|
|
|
m_args[0].m_csGUI->lock();
|
2016-11-17 00:12:59 +00:00
|
|
|
m_args[0].m_mouseCommands.push_back(cmd);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->unlock();
|
2015-09-04 18:28:08 +00:00
|
|
|
//remove p2p
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
//printf("button=%d, state=%d\n",button,state);
|
|
|
|
return false;
|
|
|
|
}
|
2017-01-26 03:17:57 +00:00
|
|
|
virtual bool keyboardCallback(int key, int state){
|
|
|
|
if (key=='w' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportPos1[0]+=0.1;
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
if (key=='s' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportPos1[0]-=0.1;
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
if (key=='a' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportPos1[1]-=0.1;
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
if (key=='d' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportPos1[1]+=0.1;
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
if (key=='q' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportPos1[2]+=0.1;
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
if (key=='e' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportPos1[2]-=0.1;
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
if (key=='z' && state)
|
|
|
|
{
|
|
|
|
gVRTeleportRotZ+=0.1;
|
|
|
|
gVRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
|
|
|
|
saveCurrentSettingsVR();
|
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
2015-08-07 07:13:26 +00:00
|
|
|
|
|
|
|
virtual void setSharedMemoryKey(int key)
|
|
|
|
{
|
|
|
|
m_physicsServer.setSharedMemoryKey(key);
|
|
|
|
}
|
|
|
|
|
2016-10-09 01:40:09 +00:00
|
|
|
virtual void processCommandLineArgs(int argc, char* argv[])
|
|
|
|
{
|
|
|
|
b3CommandLineArgs args(argc,argv);
|
2016-12-03 01:44:00 +00:00
|
|
|
loadCurrentSettingsVR(args);
|
2016-12-29 05:51:54 +00:00
|
|
|
int shmemKey;
|
|
|
|
|
|
|
|
if (args.GetCmdLineArgument("sharedMemoryKey", shmemKey))
|
|
|
|
{
|
|
|
|
setSharedMemoryKey(shmemKey);
|
|
|
|
}
|
|
|
|
|
2017-01-26 03:17:57 +00:00
|
|
|
if (args.GetCmdLineArgument("camPosX", gVRTeleportPos1[0]))
|
2016-11-17 00:12:59 +00:00
|
|
|
{
|
2017-01-26 03:17:57 +00:00
|
|
|
printf("camPosX=%f\n", gVRTeleportPos1[0]);
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
|
|
|
|
2017-01-26 03:17:57 +00:00
|
|
|
if (args.GetCmdLineArgument("camPosY", gVRTeleportPos1[1]))
|
2016-11-17 00:12:59 +00:00
|
|
|
{
|
2017-01-26 03:17:57 +00:00
|
|
|
printf("camPosY=%f\n", gVRTeleportPos1[1]);
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
|
|
|
|
2017-01-26 03:17:57 +00:00
|
|
|
if (args.GetCmdLineArgument("camPosZ", gVRTeleportPos1[2]))
|
2016-11-17 00:12:59 +00:00
|
|
|
{
|
2017-01-26 03:17:57 +00:00
|
|
|
printf("camPosZ=%f\n", gVRTeleportPos1[2]);
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
float camRotZ = 0.f;
|
|
|
|
if (args.GetCmdLineArgument("camRotZ", camRotZ))
|
|
|
|
{
|
|
|
|
printf("camRotZ = %f\n", camRotZ);
|
|
|
|
btQuaternion ornZ(btVector3(0, 0, 1), camRotZ);
|
2017-01-26 03:17:57 +00:00
|
|
|
gVRTeleportOrn = ornZ;
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
|
|
|
|
2016-10-23 14:14:50 +00:00
|
|
|
if (args.CheckCmdLineFlag("robotassets"))
|
2016-10-09 01:40:09 +00:00
|
|
|
{
|
2016-12-27 05:08:10 +00:00
|
|
|
gCreateDefaultRobotAssets = true;
|
2016-10-09 01:40:09 +00:00
|
|
|
}
|
|
|
|
|
2016-10-23 14:14:50 +00:00
|
|
|
if (args.CheckCmdLineFlag("norobotassets"))
|
|
|
|
{
|
2017-01-20 19:48:33 +00:00
|
|
|
gCreateDefaultRobotAssets = false;
|
2016-10-23 14:14:50 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
}
|
2015-08-06 18:59:31 +00:00
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
};
|
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
#ifdef B3_USE_MIDI
|
|
|
|
static bool chooseMidiPort(RtMidiIn *rtmidi)
|
|
|
|
{
|
|
|
|
/*
|
|
|
|
|
|
|
|
std::cout << "\nWould you like to open a virtual input port? [y/N] ";
|
|
|
|
|
|
|
|
std::string keyHit;
|
|
|
|
std::getline( std::cin, keyHit );
|
|
|
|
if ( keyHit == "y" ) {
|
|
|
|
rtmidi->openVirtualPort();
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
*/
|
|
|
|
|
|
|
|
std::string portName;
|
|
|
|
unsigned int i = 0, nPorts = rtmidi->getPortCount();
|
|
|
|
if (nPorts == 0) {
|
|
|
|
std::cout << "No midi input ports available!" << std::endl;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (nPorts > 0) {
|
|
|
|
std::cout << "\nOpening midi input port " << rtmidi->getPortName() << std::endl;
|
|
|
|
}
|
|
|
|
|
|
|
|
// std::getline( std::cin, keyHit ); // used to clear out stdin
|
|
|
|
rtmidi->openPort(i);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
#endif //B3_USE_MIDI
|
|
|
|
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem, int options)
|
2015-07-14 22:30:17 +00:00
|
|
|
:SharedMemoryCommon(helper),
|
2016-03-10 22:36:46 +00:00
|
|
|
m_physicsServer(sharedMem),
|
2015-08-06 18:59:31 +00:00
|
|
|
m_wantsShutdown(false),
|
2015-11-01 20:48:15 +00:00
|
|
|
m_isConnected(false),
|
2017-01-16 06:26:11 +00:00
|
|
|
m_replay(false)
|
|
|
|
//m_options(options)
|
2016-10-14 22:06:09 +00:00
|
|
|
#ifdef BT_ENABLE_VR
|
|
|
|
,m_tinyVrGui(0)
|
|
|
|
#endif
|
2015-07-14 22:30:17 +00:00
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
#ifdef B3_USE_MIDI
|
|
|
|
m_midi = new RtMidiIn();
|
|
|
|
chooseMidiPort(m_midi);
|
|
|
|
m_midi->setCallback(&midiCallback);
|
|
|
|
// Don't ignore sysex, timing, or active sensing messages.
|
|
|
|
m_midi->ignoreTypes(false, false, false);
|
|
|
|
|
|
|
|
#endif
|
2016-07-08 02:24:44 +00:00
|
|
|
m_multiThreadedHelper = helper;
|
2016-12-23 23:20:04 +00:00
|
|
|
// b3Printf("Started PhysicsServer\n");
|
2015-07-14 22:30:17 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
PhysicsServerExample::~PhysicsServerExample()
|
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
#ifdef B3_USE_MIDI
|
|
|
|
delete m_midi;
|
|
|
|
m_midi = 0;
|
|
|
|
#endif
|
2016-10-14 22:06:09 +00:00
|
|
|
#ifdef BT_ENABLE_VR
|
|
|
|
delete m_tinyVrGui;
|
|
|
|
#endif
|
2017-01-10 22:57:16 +00:00
|
|
|
|
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
bool deInitializeSharedMemory = true;
|
|
|
|
m_physicsServer.disconnectSharedMemory(deInitializeSharedMemory);
|
2015-08-06 18:59:31 +00:00
|
|
|
m_isConnected = false;
|
2017-01-10 22:57:16 +00:00
|
|
|
delete m_multiThreadedHelper;
|
2015-08-06 18:59:31 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
bool PhysicsServerExample::isConnected()
|
|
|
|
{
|
|
|
|
return m_isConnected;
|
2015-07-14 22:30:17 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
void PhysicsServerExample::initPhysics()
|
|
|
|
{
|
|
|
|
///for this testing we use Z-axis up
|
|
|
|
int upAxis = 2;
|
|
|
|
m_guiHelper->setUpAxis(upAxis);
|
|
|
|
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
|
2015-08-07 07:13:26 +00:00
|
|
|
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
m_threadSupport = createMotionThreadSupport(MAX_MOTION_NUM_THREADS);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
for (int i=0;i<m_threadSupport->getNumTasks();i++)
|
|
|
|
{
|
|
|
|
MotionThreadLocalStorage* storage = (MotionThreadLocalStorage*) m_threadSupport->getThreadLocalMemory(i);
|
|
|
|
b3Assert(storage);
|
|
|
|
storage->threadId = i;
|
|
|
|
//storage->m_sharedMem = data->m_sharedMem;
|
|
|
|
}
|
2016-05-18 23:21:40 +00:00
|
|
|
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
|
|
|
|
for (int w=0;w<MAX_MOTION_NUM_THREADS;w++)
|
|
|
|
{
|
|
|
|
m_args[w].m_cs = m_threadSupport->createCriticalSection();
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[w].m_cs2 = m_threadSupport->createCriticalSection();
|
|
|
|
m_args[w].m_cs3 = m_threadSupport->createCriticalSection();
|
|
|
|
m_args[w].m_csGUI = m_threadSupport->createCriticalSection();
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
m_args[w].m_cs->setSharedParam(0,eMotionIsUnInitialized);
|
|
|
|
int numMoving = 0;
|
|
|
|
m_args[w].m_positions.resize(numMoving);
|
|
|
|
m_args[w].m_physicsServerPtr = &m_physicsServer;
|
2017-01-16 06:26:11 +00:00
|
|
|
//int index = 0;
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*) &this->m_args[w], w);
|
2016-08-13 19:21:18 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
while (m_args[w].m_cs->getSharedParam(0)==eMotionIsUnInitialized)
|
|
|
|
{
|
2016-08-13 19:21:18 +00:00
|
|
|
b3Clock::usleep(1000);
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
m_args[0].m_cs->setSharedParam(1,eGUIHelperIdle);
|
|
|
|
m_multiThreadedHelper->setCriticalSection(m_args[0].m_cs);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->setCriticalSection2(m_args[0].m_cs2);
|
|
|
|
m_multiThreadedHelper->setCriticalSection3(m_args[0].m_cs3);
|
|
|
|
m_multiThreadedHelper->setCriticalSectionGUI(m_args[0].m_csGUI);
|
|
|
|
|
|
|
|
m_args[0].m_cs2->lock();
|
|
|
|
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
m_isConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
|
2015-07-14 22:30:17 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
void PhysicsServerExample::exitPhysics()
|
|
|
|
{
|
|
|
|
for (int i=0;i<MAX_MOTION_NUM_THREADS;i++)
|
|
|
|
{
|
|
|
|
m_args[i].m_cs->lock();
|
|
|
|
m_args[i].m_cs->setSharedParam(0,eRequestTerminateMotion);
|
|
|
|
m_args[i].m_cs->unlock();
|
|
|
|
}
|
|
|
|
int numActiveThreads = MAX_MOTION_NUM_THREADS;
|
|
|
|
|
|
|
|
while (numActiveThreads)
|
|
|
|
{
|
|
|
|
int arg0,arg1;
|
|
|
|
if (m_threadSupport->isTaskCompleted(&arg0,&arg1,0))
|
|
|
|
{
|
|
|
|
numActiveThreads--;
|
|
|
|
printf("numActiveThreads = %d\n",numActiveThreads);
|
|
|
|
|
|
|
|
} else
|
|
|
|
{
|
2016-08-13 19:21:18 +00:00
|
|
|
b3Clock::usleep(1000);
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
2017-01-12 16:06:40 +00:00
|
|
|
//we need to call 'stepSimulation' to make sure that
|
|
|
|
//other threads get out of blocking state (workerThreadWait)
|
|
|
|
stepSimulation(0);
|
2016-07-08 02:24:44 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
printf("stopping threads\n");
|
|
|
|
|
2017-01-10 22:57:16 +00:00
|
|
|
m_threadSupport->deleteCriticalSection(m_args[0].m_cs);
|
|
|
|
m_threadSupport->deleteCriticalSection(m_args[0].m_cs2);
|
|
|
|
m_threadSupport->deleteCriticalSection(m_args[0].m_cs3);
|
|
|
|
m_threadSupport->deleteCriticalSection(m_args[0].m_csGUI);
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
delete m_threadSupport;
|
|
|
|
m_threadSupport = 0;
|
|
|
|
|
2016-07-09 22:09:09 +00:00
|
|
|
//m_physicsServer.resetDynamicsWorld();
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
bool PhysicsServerExample::wantsTermination()
|
|
|
|
{
|
|
|
|
return m_wantsShutdown;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void PhysicsServerExample::stepSimulation(float deltaTime)
|
|
|
|
{
|
2016-12-29 05:51:54 +00:00
|
|
|
BT_PROFILE("PhysicsServerExample::stepSimulation");
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
//this->m_physicsServer.processClientCommands();
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
|
|
|
|
{
|
|
|
|
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
|
|
|
|
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
|
|
|
|
m_multiThreadedHelper->m_userDebugLines.pop_back();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
|
|
|
|
{
|
|
|
|
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
|
|
|
|
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
|
|
|
|
m_multiThreadedHelper->m_userDebugText.pop_back();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
//check if any graphics related tasks are requested
|
|
|
|
|
|
|
|
switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1))
|
|
|
|
{
|
|
|
|
case eGUIHelperCreateCollisionShapeGraphicsObject:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->createCollisionShapeGraphicsObject(m_multiThreadedHelper->m_colShape);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-07-08 02:24:44 +00:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case eGUIHelperCreateCollisionObjectGraphicsObject:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->createCollisionObjectGraphicsObject(m_multiThreadedHelper->m_obj,
|
|
|
|
m_multiThreadedHelper->m_color2);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
break;
|
|
|
|
}
|
2016-09-22 15:50:28 +00:00
|
|
|
case eGUIHelperCreateRigidBodyGraphicsObject:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->createRigidBodyGraphicsObject(m_multiThreadedHelper->m_body,m_multiThreadedHelper->m_color3);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-09-22 15:50:28 +00:00
|
|
|
break;
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
case eGUIHelperRegisterTexture:
|
|
|
|
{
|
|
|
|
|
|
|
|
m_multiThreadedHelper->m_textureId = m_multiThreadedHelper->m_childGuiHelper->registerTexture(m_multiThreadedHelper->m_texels,
|
|
|
|
m_multiThreadedHelper->m_textureWidth,m_multiThreadedHelper->m_textureHeight);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-07-08 02:24:44 +00:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case eGUIHelperRegisterGraphicsShape:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape(
|
|
|
|
m_multiThreadedHelper->m_vertices,
|
|
|
|
m_multiThreadedHelper->m_numvertices,
|
|
|
|
m_multiThreadedHelper->m_indices,
|
|
|
|
m_multiThreadedHelper->m_numIndices,
|
|
|
|
m_multiThreadedHelper->m_primitiveType,
|
|
|
|
m_multiThreadedHelper->m_textureId);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-07-08 02:24:44 +00:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case eGUIHelperRegisterGraphicsInstance:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance(
|
|
|
|
m_multiThreadedHelper->m_shapeIndex,
|
|
|
|
m_multiThreadedHelper->m_position,
|
|
|
|
m_multiThreadedHelper->m_quaternion,
|
|
|
|
m_multiThreadedHelper->m_color,
|
|
|
|
m_multiThreadedHelper->m_scaling);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-07-08 02:24:44 +00:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case eGUIHelperRemoveAllGraphicsInstances:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->removeAllGraphicsInstances();
|
2016-12-29 05:51:54 +00:00
|
|
|
if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
|
|
|
|
{
|
2017-01-16 16:23:49 +00:00
|
|
|
int numRenderInstances;
|
|
|
|
numRenderInstances = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
|
2016-12-29 05:51:54 +00:00
|
|
|
b3Assert(numRenderInstances==0);
|
|
|
|
}
|
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-07-09 22:09:09 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
break;
|
|
|
|
}
|
2016-08-08 21:23:44 +00:00
|
|
|
|
|
|
|
case eGUIHelperCopyCameraImageData:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
|
2017-01-16 16:23:49 +00:00
|
|
|
m_multiThreadedHelper->m_projectionMatrix,
|
|
|
|
m_multiThreadedHelper->m_pixelsRGBA,
|
|
|
|
m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
|
|
|
|
m_multiThreadedHelper->m_depthBuffer,
|
|
|
|
m_multiThreadedHelper->m_depthBufferSizeInPixels,
|
|
|
|
m_multiThreadedHelper->m_segmentationMaskBuffer,
|
|
|
|
m_multiThreadedHelper->m_segmentationMaskBufferSizeInPixels,
|
|
|
|
m_multiThreadedHelper->m_startPixelIndex,
|
|
|
|
m_multiThreadedHelper->m_destinationWidth,
|
|
|
|
m_multiThreadedHelper->m_destinationHeight,
|
|
|
|
m_multiThreadedHelper->m_numPixelsCopied);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-08-08 21:23:44 +00:00
|
|
|
break;
|
|
|
|
}
|
2016-11-12 02:07:42 +00:00
|
|
|
case eGUIHelperAutogenerateGraphicsObjects:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->autogenerateGraphicsObjects(m_multiThreadedHelper->m_dynamicsWorld);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-11-12 02:07:42 +00:00
|
|
|
break;
|
|
|
|
}
|
2016-11-14 15:39:34 +00:00
|
|
|
|
2016-11-20 23:38:42 +00:00
|
|
|
case eGUIUserDebugAddText:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-11-20 23:38:42 +00:00
|
|
|
break;
|
|
|
|
}
|
2017-01-17 23:42:32 +00:00
|
|
|
case eGUIUserDebugAddParameter:
|
|
|
|
{
|
|
|
|
UserDebugParameter* param = new UserDebugParameter(m_multiThreadedHelper->m_tmpParam);
|
|
|
|
m_multiThreadedHelper->m_userDebugParams.push_back(param);
|
|
|
|
|
|
|
|
{
|
|
|
|
SliderParams slider(param->m_text,¶m->m_value);
|
|
|
|
slider.m_minVal=param->m_rangeMin;
|
|
|
|
slider.m_maxVal=param->m_rangeMax;
|
|
|
|
|
|
|
|
if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
|
|
|
}
|
|
|
|
|
|
|
|
//also add actual menu
|
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
|
|
|
break;
|
|
|
|
}
|
2016-11-20 23:38:42 +00:00
|
|
|
case eGUIUserDebugAddLine:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-11-20 23:38:42 +00:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case eGUIUserDebugRemoveItem:
|
|
|
|
{
|
|
|
|
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
|
|
|
|
{
|
|
|
|
if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
|
|
|
|
m_multiThreadedHelper->m_userDebugLines.pop_back();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
|
|
|
|
{
|
|
|
|
if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
|
|
|
|
m_multiThreadedHelper->m_userDebugText.pop_back();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-11-20 23:38:42 +00:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case eGUIUserDebugRemoveAllItems:
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_userDebugLines.clear();
|
|
|
|
m_multiThreadedHelper->m_userDebugText.clear();
|
|
|
|
m_multiThreadedHelper->m_uidGenerator = 0;
|
2016-12-29 05:51:54 +00:00
|
|
|
m_multiThreadedHelper->mainThreadRelease();
|
2016-11-20 23:38:42 +00:00
|
|
|
break;
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
case eGUIHelperIdle:
|
2016-11-14 15:39:34 +00:00
|
|
|
{
|
|
|
|
break;
|
|
|
|
}
|
2016-07-08 02:24:44 +00:00
|
|
|
default:
|
|
|
|
{
|
2016-11-14 15:39:34 +00:00
|
|
|
btAssert(0);
|
2016-07-08 02:24:44 +00:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
2017-01-06 02:30:01 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
{
|
|
|
|
if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->writeTransforms();
|
|
|
|
}
|
|
|
|
}
|
2015-07-14 22:30:17 +00:00
|
|
|
}
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
static float vrOffset[16]={1,0,0,0,
|
|
|
|
0,1,0,0,
|
|
|
|
0,0,1,0,
|
|
|
|
0,0,0,0};
|
|
|
|
|
2016-07-09 22:09:09 +00:00
|
|
|
|
2016-09-09 18:28:38 +00:00
|
|
|
extern int gDroppedSimulationSteps;
|
|
|
|
extern int gNumSteps;
|
|
|
|
extern double gDtInSec;
|
|
|
|
extern double gSubStep;
|
2017-01-06 01:41:58 +00:00
|
|
|
extern int gVRTrackingObjectUniqueId;
|
|
|
|
extern btTransform gVRTrackingObjectTr;
|
2016-11-17 00:12:59 +00:00
|
|
|
|
2016-12-27 21:20:12 +00:00
|
|
|
struct LineSegment
|
|
|
|
{
|
|
|
|
btVector3 m_from;
|
|
|
|
btVector3 m_to;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct ColorWidth
|
|
|
|
{
|
|
|
|
btVector3FloatData m_color;
|
|
|
|
int width;
|
|
|
|
int getHash() const
|
|
|
|
{
|
|
|
|
unsigned char r = (unsigned char) m_color.m_floats[0]*255;
|
|
|
|
unsigned char g = (unsigned char) m_color.m_floats[1]*255;
|
|
|
|
unsigned char b = (unsigned char) m_color.m_floats[2]*255;
|
|
|
|
unsigned char w = width;
|
|
|
|
return r+(256*g)+(256*256*b)+(256*256*256*w);
|
|
|
|
}
|
|
|
|
bool equals(const ColorWidth& other) const
|
|
|
|
{
|
|
|
|
bool same = ((width == other.width) && (m_color.m_floats[0] == other.m_color.m_floats[0]) &&
|
|
|
|
(m_color.m_floats[1] == other.m_color.m_floats[1]) &&
|
|
|
|
(m_color.m_floats[2] == other.m_color.m_floats[2]));
|
|
|
|
return same;
|
|
|
|
}
|
|
|
|
};
|
2016-11-17 00:12:59 +00:00
|
|
|
|
2016-11-20 01:13:56 +00:00
|
|
|
void PhysicsServerExample::drawUserDebugLines()
|
|
|
|
{
|
2017-01-16 06:26:11 +00:00
|
|
|
//static char line0[1024];
|
|
|
|
//static char line1[1024];
|
2016-11-20 01:13:56 +00:00
|
|
|
|
|
|
|
//draw all user-debug-lines
|
|
|
|
|
|
|
|
//add array of lines
|
2016-09-09 18:28:38 +00:00
|
|
|
|
2016-11-20 01:13:56 +00:00
|
|
|
//draw all user- 'text3d' messages
|
|
|
|
if (m_multiThreadedHelper)
|
|
|
|
{
|
2016-11-20 23:38:42 +00:00
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
|
|
|
|
//if gBatchUserDebugLines is true, batch lines based on color+width, to reduce line draw calls
|
|
|
|
|
|
|
|
btAlignedObjectArray< btAlignedObjectArray<unsigned int> > sortedIndices;
|
|
|
|
btAlignedObjectArray< btAlignedObjectArray<btVector3FloatData> > sortedLines;
|
|
|
|
|
|
|
|
btHashMap<ColorWidth,int> hashedLines;
|
|
|
|
|
2016-11-20 01:13:56 +00:00
|
|
|
for (int i = 0; i<m_multiThreadedHelper->m_userDebugLines.size(); i++)
|
|
|
|
{
|
|
|
|
btVector3 from;
|
|
|
|
from.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
|
|
|
|
btVector3 toX;
|
|
|
|
toX.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
|
|
|
|
|
|
|
|
btVector3 color;
|
|
|
|
color.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
|
|
|
|
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
|
2016-12-27 03:40:09 +00:00
|
|
|
ColorWidth cw;
|
|
|
|
color.serializeFloat(cw.m_color);
|
|
|
|
cw.width = m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth;
|
|
|
|
int index = -1;
|
|
|
|
|
|
|
|
if (gBatchUserDebugLines)
|
|
|
|
{
|
|
|
|
int* indexPtr = hashedLines.find(cw);
|
|
|
|
if (indexPtr)
|
|
|
|
{
|
|
|
|
index = *indexPtr;
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
index = sortedLines.size();
|
|
|
|
sortedLines.expand();
|
|
|
|
sortedIndices.expand();
|
|
|
|
hashedLines.insert(cw,index);
|
|
|
|
}
|
|
|
|
btAssert(index>=0);
|
|
|
|
if (index>=0)
|
|
|
|
{
|
|
|
|
btVector3FloatData from1,toX1;
|
|
|
|
sortedIndices[index].push_back(sortedLines[index].size());
|
|
|
|
from.serializeFloat(from1);
|
|
|
|
sortedLines[index].push_back(from1);
|
|
|
|
sortedIndices[index].push_back(sortedLines[index].size());
|
|
|
|
toX.serializeFloat(toX1);
|
|
|
|
sortedLines[index].push_back(toX1);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
|
|
|
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
|
|
|
|
}
|
|
|
|
}
|
2016-11-20 01:13:56 +00:00
|
|
|
|
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
if (gBatchUserDebugLines)
|
|
|
|
{
|
|
|
|
for (int i=0;i<hashedLines.size();i++)
|
|
|
|
{
|
|
|
|
ColorWidth cw = hashedLines.getKeyAtIndex(i);
|
|
|
|
int index = *hashedLines.getAtIndex(i);
|
|
|
|
int stride = sizeof(btVector3FloatData);
|
|
|
|
const float* positions = &sortedLines[index][0].m_floats[0];
|
|
|
|
int numPoints = sortedLines[index].size();
|
|
|
|
const unsigned int* indices = &sortedIndices[index][0];
|
|
|
|
int numIndices = sortedIndices[index].size();
|
|
|
|
m_guiHelper->getAppInterface()->m_renderer->drawLines(positions,cw.m_color.m_floats,numPoints, stride, indices,numIndices,cw.width);
|
|
|
|
}
|
2016-11-20 01:13:56 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
for (int i = 0; i<m_multiThreadedHelper->m_userDebugText.size(); i++)
|
|
|
|
{
|
|
|
|
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
|
|
|
|
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
|
|
|
|
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
|
|
|
|
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
|
|
|
|
m_multiThreadedHelper->m_userDebugText[i].textSize);
|
|
|
|
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
2016-09-09 18:28:38 +00:00
|
|
|
|
2015-08-07 07:13:26 +00:00
|
|
|
void PhysicsServerExample::renderScene()
|
|
|
|
{
|
2017-01-06 01:41:58 +00:00
|
|
|
btTransform vrTrans;
|
2017-01-21 02:13:24 +00:00
|
|
|
//gVRTeleportPos1 = gVRTeleportPosLocal;
|
|
|
|
//gVRTeleportOrn = gVRTeleportOrnLocal;
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
///little VR test to follow/drive Husky vehicle
|
2017-01-06 01:41:58 +00:00
|
|
|
if (gVRTrackingObjectUniqueId >= 0)
|
2016-11-17 00:12:59 +00:00
|
|
|
{
|
2017-01-06 01:41:58 +00:00
|
|
|
btTransform vrTrans;
|
|
|
|
vrTrans.setOrigin(gVRTeleportPosLocal);
|
|
|
|
vrTrans.setRotation(gVRTeleportOrnLocal);
|
|
|
|
|
|
|
|
vrTrans = vrTrans * gVRTrackingObjectTr;
|
|
|
|
|
|
|
|
gVRTeleportPos1 = vrTrans.getOrigin();
|
|
|
|
gVRTeleportOrn = vrTrans.getRotation();
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-09-19 14:02:43 +00:00
|
|
|
B3_PROFILE("PhysicsServerExample::RenderScene");
|
2016-11-10 05:01:04 +00:00
|
|
|
|
2016-11-20 01:13:56 +00:00
|
|
|
drawUserDebugLines();
|
2016-11-10 05:01:04 +00:00
|
|
|
|
2016-10-14 22:06:09 +00:00
|
|
|
if (gEnableRealTimeSimVR)
|
|
|
|
{
|
|
|
|
|
|
|
|
static int frameCount=0;
|
2017-01-16 06:26:11 +00:00
|
|
|
//static btScalar prevTime = m_clock.getTimeSeconds();
|
2016-10-14 22:06:09 +00:00
|
|
|
frameCount++;
|
2017-01-16 06:26:11 +00:00
|
|
|
|
|
|
|
#if 0
|
|
|
|
|
2016-10-14 22:06:09 +00:00
|
|
|
static btScalar worseFps = 1000000;
|
|
|
|
int numFrames = 200;
|
|
|
|
static int count = 0;
|
|
|
|
count++;
|
|
|
|
|
|
|
|
if (0 == (count & 1))
|
|
|
|
{
|
|
|
|
btScalar curTime = m_clock.getTimeSeconds();
|
|
|
|
btScalar fps = 1. / (curTime - prevTime);
|
|
|
|
prevTime = curTime;
|
|
|
|
if (fps < worseFps)
|
|
|
|
{
|
|
|
|
worseFps = fps;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (count > numFrames)
|
|
|
|
{
|
|
|
|
count = 0;
|
|
|
|
sprintf(line0, "fps:%f frame:%d", worseFps, frameCount / 2);
|
|
|
|
sprintf(line1, "drop:%d tscale:%f dt:%f, substep %f)", gDroppedSimulationSteps, simTimeScalingFactor,gDtInSec, gSubStep);
|
|
|
|
gDroppedSimulationSteps = 0;
|
|
|
|
|
|
|
|
worseFps = 1000000;
|
|
|
|
}
|
|
|
|
}
|
2016-11-20 01:13:56 +00:00
|
|
|
#endif
|
2016-10-14 22:06:09 +00:00
|
|
|
|
|
|
|
#ifdef BT_ENABLE_VR
|
2016-10-23 14:14:50 +00:00
|
|
|
if ((gInternalSimFlags&2 ) && m_tinyVrGui==0)
|
2016-10-14 22:06:09 +00:00
|
|
|
{
|
|
|
|
ComboBoxParams comboParams;
|
|
|
|
comboParams.m_comboboxId = 0;
|
|
|
|
comboParams.m_numItems = 0;
|
|
|
|
comboParams.m_startItem = 0;
|
|
|
|
comboParams.m_callback = 0;//MyComboBoxCallback;
|
|
|
|
comboParams.m_userPointer = 0;//this;
|
|
|
|
|
|
|
|
m_tinyVrGui = new TinyVRGui(comboParams,this->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface());
|
|
|
|
m_tinyVrGui->init();
|
|
|
|
}
|
|
|
|
|
|
|
|
if (m_tinyVrGui)
|
|
|
|
{
|
2016-09-19 14:02:43 +00:00
|
|
|
|
2016-10-14 22:06:09 +00:00
|
|
|
b3Transform tr;tr.setIdentity();
|
|
|
|
tr.setOrigin(b3MakeVector3(gVRController2Pos[0],gVRController2Pos[1],gVRController2Pos[2]));
|
|
|
|
tr.setRotation(b3Quaternion(gVRController2Orn[0],gVRController2Orn[1],gVRController2Orn[2],gVRController2Orn[3]));
|
|
|
|
tr = tr*b3Transform(b3Quaternion(0,0,-SIMD_HALF_PI),b3MakeVector3(0,0,0));
|
|
|
|
b3Scalar dt = 0.01;
|
|
|
|
m_tinyVrGui->clearTextArea();
|
2016-11-21 00:22:20 +00:00
|
|
|
static char line0[1024];
|
|
|
|
static char line1[1024];
|
|
|
|
|
2016-10-14 22:06:09 +00:00
|
|
|
m_tinyVrGui->grapicalPrintf(line0,0,0,0,0,0,255);
|
|
|
|
m_tinyVrGui->grapicalPrintf(line1,0,16,255,255,255,255);
|
|
|
|
|
|
|
|
m_tinyVrGui->tick(dt,tr);
|
|
|
|
}
|
|
|
|
#endif//BT_ENABLE_VR
|
|
|
|
}
|
2015-08-07 07:13:26 +00:00
|
|
|
///debug rendering
|
2016-07-08 02:24:44 +00:00
|
|
|
//m_args[0].m_cs->lock();
|
|
|
|
|
2016-09-15 23:57:00 +00:00
|
|
|
//gVRTeleportPos[0] += 0.01;
|
2016-11-17 00:12:59 +00:00
|
|
|
btTransform tr2a, tr2;
|
|
|
|
tr2a.setIdentity();
|
|
|
|
tr2.setIdentity();
|
|
|
|
tr2.setOrigin(gVRTeleportPos1);
|
|
|
|
tr2a.setRotation(gVRTeleportOrn);
|
|
|
|
btTransform trTotal = tr2*tr2a;
|
|
|
|
btTransform trInv = trTotal.inverse();
|
|
|
|
|
|
|
|
btMatrix3x3 vrOffsetRot;
|
|
|
|
vrOffsetRot.setRotation(trInv.getRotation());
|
|
|
|
for (int i = 0; i < 3; i++)
|
|
|
|
{
|
|
|
|
for (int j = 0; j < 3; j++)
|
|
|
|
{
|
|
|
|
vrOffset[i + 4 * j] = vrOffsetRot[i][j];
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
vrOffset[12]= trInv.getOrigin()[0];
|
|
|
|
vrOffset[13]= trInv.getOrigin()[1];
|
|
|
|
vrOffset[14]= trInv.getOrigin()[2];
|
2016-09-08 22:15:58 +00:00
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
|
|
|
|
{
|
|
|
|
m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->
|
2016-09-08 22:15:58 +00:00
|
|
|
getActiveCamera()->setVRCameraOffsetTransform(vrOffset);
|
2016-12-29 05:51:54 +00:00
|
|
|
}
|
2015-08-07 07:13:26 +00:00
|
|
|
m_physicsServer.renderScene();
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
for (int i=0;i<MAX_VR_CONTROLLERS;i++)
|
2016-07-18 06:50:11 +00:00
|
|
|
{
|
2016-09-08 22:15:58 +00:00
|
|
|
if (m_args[0].m_isVrControllerPicking[i] || m_args[0].m_isVrControllerDragging[i])
|
|
|
|
{
|
|
|
|
btVector3 from = m_args[0].m_vrControllerPos[i];
|
|
|
|
btMatrix3x3 mat(m_args[0].m_vrControllerOrn[i]);
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
btVector3 toX = from+mat.getColumn(0);
|
|
|
|
btVector3 toY = from+mat.getColumn(1);
|
|
|
|
btVector3 toZ = from+mat.getColumn(2);
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
int width = 2;
|
2016-07-18 06:50:11 +00:00
|
|
|
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
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);
|
2016-07-18 06:50:11 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
2016-07-18 06:50:11 +00:00
|
|
|
}
|
2016-07-09 22:09:09 +00:00
|
|
|
|
|
|
|
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
|
|
|
|
{
|
2016-12-11 17:28:36 +00:00
|
|
|
if (!gEnableRealTimeSimVR)
|
|
|
|
{
|
|
|
|
gEnableRealTimeSimVR = true;
|
|
|
|
m_physicsServer.enableRealTimeSimulation(1);
|
|
|
|
}
|
2016-09-22 15:50:28 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-07-09 22:09:09 +00:00
|
|
|
|
2016-07-08 02:24:44 +00:00
|
|
|
//m_args[0].m_cs->unlock();
|
2015-08-07 07:13:26 +00:00
|
|
|
}
|
|
|
|
|
|
|
|
void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
|
|
|
|
{
|
2016-11-20 01:13:56 +00:00
|
|
|
drawUserDebugLines();
|
|
|
|
|
2015-08-07 07:13:26 +00:00
|
|
|
///debug rendering
|
|
|
|
m_physicsServer.physicsDebugDraw(debugDrawFlags);
|
|
|
|
|
|
|
|
}
|
|
|
|
|
2015-07-14 22:30:17 +00:00
|
|
|
|
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
btVector3 PhysicsServerExample::getRayTo(int x,int y)
|
|
|
|
{
|
|
|
|
CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
if (!renderer)
|
|
|
|
{
|
|
|
|
btAssert(0);
|
|
|
|
return btVector3(0,0,0);
|
|
|
|
}
|
|
|
|
|
|
|
|
float top = 1.f;
|
|
|
|
float bottom = -1.f;
|
|
|
|
float nearPlane = 1.f;
|
|
|
|
float tanFov = (top-bottom)*0.5f / nearPlane;
|
|
|
|
float fov = btScalar(2.0) * btAtan(tanFov);
|
|
|
|
|
|
|
|
btVector3 camPos,camTarget;
|
|
|
|
renderer->getActiveCamera()->getCameraPosition(camPos);
|
|
|
|
renderer->getActiveCamera()->getCameraTargetPosition(camTarget);
|
2016-09-08 22:15:58 +00:00
|
|
|
|
2015-09-04 18:28:08 +00:00
|
|
|
btVector3 rayFrom = camPos;
|
|
|
|
btVector3 rayForward = (camTarget-camPos);
|
|
|
|
rayForward.normalize();
|
|
|
|
float farPlane = 10000.f;
|
|
|
|
rayForward*= farPlane;
|
|
|
|
|
|
|
|
btVector3 rightOffset;
|
|
|
|
btVector3 cameraUp=btVector3(0,0,0);
|
|
|
|
cameraUp[m_guiHelper->getAppInterface()->getUpAxis()]=1;
|
|
|
|
|
|
|
|
btVector3 vertical = cameraUp;
|
|
|
|
|
|
|
|
btVector3 hor;
|
|
|
|
hor = rayForward.cross(vertical);
|
|
|
|
hor.normalize();
|
|
|
|
vertical = hor.cross(rayForward);
|
|
|
|
vertical.normalize();
|
|
|
|
|
|
|
|
float tanfov = tanf(0.5f*fov);
|
|
|
|
|
|
|
|
|
|
|
|
hor *= 2.f * farPlane * tanfov;
|
|
|
|
vertical *= 2.f * farPlane * tanfov;
|
|
|
|
|
|
|
|
btScalar aspect;
|
|
|
|
float width = float(renderer->getScreenWidth());
|
|
|
|
float height = float (renderer->getScreenHeight());
|
|
|
|
|
|
|
|
aspect = width / height;
|
|
|
|
|
|
|
|
hor*=aspect;
|
|
|
|
|
|
|
|
|
|
|
|
btVector3 rayToCenter = rayFrom + rayForward;
|
|
|
|
btVector3 dHor = hor * 1.f/width;
|
|
|
|
btVector3 dVert = vertical * 1.f/height;
|
|
|
|
|
|
|
|
|
|
|
|
btVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical;
|
|
|
|
rayTo += btScalar(x) * dHor;
|
|
|
|
rayTo -= btScalar(y) * dVert;
|
|
|
|
return rayTo;
|
|
|
|
}
|
2015-07-14 22:30:17 +00:00
|
|
|
|
2015-10-29 18:25:50 +00:00
|
|
|
|
|
|
|
extern int gSharedMemoryKey;
|
|
|
|
|
|
|
|
class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
|
|
|
|
{
|
2016-07-08 02:24:44 +00:00
|
|
|
|
|
|
|
MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(),options.m_guiHelper);
|
|
|
|
|
|
|
|
PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
|
|
|
|
options.m_sharedMem,
|
|
|
|
options.m_option);
|
|
|
|
|
2015-10-29 18:25:50 +00:00
|
|
|
if (gSharedMemoryKey>=0)
|
|
|
|
{
|
|
|
|
example->setSharedMemoryKey(gSharedMemoryKey);
|
|
|
|
}
|
|
|
|
if (options.m_option & PHYSICS_SERVER_ENABLE_COMMAND_LOGGING)
|
|
|
|
{
|
|
|
|
example->enableCommandLogging();
|
|
|
|
}
|
2015-10-30 17:30:48 +00:00
|
|
|
if (options.m_option & PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG)
|
|
|
|
{
|
|
|
|
example->replayFromLogFile();
|
|
|
|
}
|
2015-10-29 18:25:50 +00:00
|
|
|
return example;
|
2016-05-18 23:21:40 +00:00
|
|
|
|
2015-10-29 18:25:50 +00:00
|
|
|
}
|
2016-07-03 01:53:19 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
|
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4])
|
|
|
|
{
|
2016-09-08 22:15:58 +00:00
|
|
|
//printf("controllerId %d, button=%d\n",controllerId, button);
|
|
|
|
|
2016-09-09 18:28:38 +00:00
|
|
|
if (controllerId<0 || controllerId>=MAX_VR_CONTROLLERS)
|
2016-09-08 22:15:58 +00:00
|
|
|
return;
|
|
|
|
|
2016-09-15 23:57:00 +00:00
|
|
|
if (gGraspingController < 0)
|
2016-12-03 01:44:00 +00:00
|
|
|
{
|
2016-09-15 23:57:00 +00:00
|
|
|
gGraspingController = controllerId;
|
2016-12-03 01:44:00 +00:00
|
|
|
gEnableKukaControl = true;
|
|
|
|
}
|
2016-12-27 03:40:09 +00:00
|
|
|
|
|
|
|
btTransform trLocal;
|
|
|
|
trLocal.setIdentity();
|
|
|
|
trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
|
|
|
|
|
|
|
|
btTransform trOrg;
|
|
|
|
trOrg.setIdentity();
|
|
|
|
trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
|
|
|
|
trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
|
|
|
|
|
|
|
|
btTransform tr2a;
|
|
|
|
tr2a.setIdentity();
|
|
|
|
btTransform tr2;
|
|
|
|
tr2.setIdentity();
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
tr2.setOrigin(gVRTeleportPos1);
|
|
|
|
tr2a.setRotation(gVRTeleportOrn);
|
|
|
|
|
|
|
|
|
|
|
|
btTransform trTotal = tr2*tr2a*trOrg*trLocal;
|
|
|
|
|
|
|
|
|
2016-09-12 18:10:20 +00:00
|
|
|
if (controllerId != gGraspingController)
|
2016-09-08 22:15:58 +00:00
|
|
|
{
|
2016-09-12 18:10:20 +00:00
|
|
|
if (button == 1 && state == 0)
|
|
|
|
{
|
2016-12-27 05:08:10 +00:00
|
|
|
//gResetSimulation = true;
|
2016-12-31 19:35:56 +00:00
|
|
|
gVRTeleportPos1 = gLastPickPos;
|
2016-09-12 18:10:20 +00:00
|
|
|
}
|
2016-09-22 15:50:28 +00:00
|
|
|
} else
|
|
|
|
{
|
|
|
|
if (button == 1)
|
|
|
|
{
|
|
|
|
if (state == 1)
|
|
|
|
{
|
|
|
|
gDebugRenderToggle = 1;
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
gDebugRenderToggle = 0;
|
2016-11-30 01:08:47 +00:00
|
|
|
#if 0//it confuses people, make it into a debug option in a VR GUI?
|
2016-09-22 15:50:28 +00:00
|
|
|
if (simTimeScalingFactor==0)
|
|
|
|
{
|
|
|
|
simTimeScalingFactor = 1;
|
2016-09-24 18:25:05 +00:00
|
|
|
} else
|
2016-09-22 15:50:28 +00:00
|
|
|
{
|
2016-09-24 18:25:05 +00:00
|
|
|
if (simTimeScalingFactor==1)
|
|
|
|
{
|
|
|
|
simTimeScalingFactor = 0.25;
|
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
|
|
|
simTimeScalingFactor = 0;
|
|
|
|
}
|
2016-09-22 15:50:28 +00:00
|
|
|
}
|
2016-11-30 01:08:47 +00:00
|
|
|
#endif
|
2016-09-22 15:50:28 +00:00
|
|
|
}
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
|
|
|
|
}
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
if (button==32 && state==0)
|
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
if (controllerId == gGraspingController)
|
|
|
|
{
|
|
|
|
gCreateObjectSimVR = 1;
|
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
2016-11-30 01:08:47 +00:00
|
|
|
// gEnableKukaControl = !gEnableKukaControl;
|
2016-11-17 00:12:59 +00:00
|
|
|
}
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
|
|
|
|
2016-09-09 21:30:37 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
if (button==1)
|
|
|
|
{
|
|
|
|
m_args[0].m_isVrControllerTeleporting[controllerId] = true;
|
|
|
|
}
|
|
|
|
|
2016-09-12 18:10:20 +00:00
|
|
|
if (controllerId == gGraspingController && (button == 33))
|
2016-09-08 22:15:58 +00:00
|
|
|
{
|
2017-01-16 21:05:26 +00:00
|
|
|
gVRGripperClosed =(state!=0);
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
2016-09-09 21:30:37 +00:00
|
|
|
else
|
2016-09-08 22:15:58 +00:00
|
|
|
{
|
2016-09-09 21:30:37 +00:00
|
|
|
|
2016-09-11 10:35:12 +00:00
|
|
|
if (button == 33)
|
2016-09-09 21:30:37 +00:00
|
|
|
{
|
|
|
|
m_args[0].m_isVrControllerPicking[controllerId] = (state != 0);
|
|
|
|
m_args[0].m_isVrControllerReleasing[controllerId] = (state == 0);
|
|
|
|
}
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
|
2016-09-09 21:30:37 +00:00
|
|
|
if ((button == 33) || (button == 1))
|
|
|
|
{
|
2016-11-17 00:12:59 +00:00
|
|
|
// m_args[0].m_vrControllerPos[controllerId].setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
|
|
|
|
// m_args[0].m_vrControllerOrn[controllerId].setValue(orn[0], orn[1], orn[2], orn[3]);
|
|
|
|
m_args[0].m_vrControllerPos[controllerId] = trTotal.getOrigin();
|
|
|
|
m_args[0].m_vrControllerOrn[controllerId] = trTotal.getRotation();
|
2016-09-09 21:30:37 +00:00
|
|
|
}
|
2016-11-17 00:12:59 +00:00
|
|
|
|
2016-09-08 22:15:58 +00:00
|
|
|
}
|
2016-12-27 03:40:09 +00:00
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->lock();
|
2016-12-27 03:40:09 +00:00
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_numButtonEvents++;
|
|
|
|
if (state)
|
|
|
|
{
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_buttons[button]|=eButtonIsDown+eButtonTriggered;
|
|
|
|
} else
|
|
|
|
{
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_buttons[button]|=eButtonReleased;
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_buttons[button] &= ~eButtonIsDown;
|
|
|
|
}
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->unlock();
|
2016-07-18 06:50:11 +00:00
|
|
|
}
|
|
|
|
|
2016-09-15 23:57:00 +00:00
|
|
|
|
|
|
|
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
|
2016-07-18 06:50:11 +00:00
|
|
|
{
|
2016-09-08 22:15:58 +00:00
|
|
|
|
2016-09-09 18:28:38 +00:00
|
|
|
if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS)
|
|
|
|
{
|
|
|
|
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
|
|
|
|
return;
|
|
|
|
}
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
btTransform trLocal;
|
|
|
|
trLocal.setIdentity();
|
|
|
|
trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
|
|
|
|
|
|
|
|
btTransform trOrg;
|
|
|
|
trOrg.setIdentity();
|
|
|
|
trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
|
|
|
|
trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
|
|
|
|
|
|
|
|
btTransform tr2a;
|
|
|
|
tr2a.setIdentity();
|
|
|
|
btTransform tr2;
|
|
|
|
tr2.setIdentity();
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
tr2.setOrigin(gVRTeleportPos1);
|
|
|
|
tr2a.setRotation(gVRTeleportOrn);
|
|
|
|
|
|
|
|
|
|
|
|
btTransform trTotal = tr2*tr2a*trOrg*trLocal;
|
|
|
|
|
2016-09-12 18:10:20 +00:00
|
|
|
if (controllerId == gGraspingController)
|
2016-09-09 21:30:37 +00:00
|
|
|
{
|
2016-09-15 23:57:00 +00:00
|
|
|
gVRGripperAnalog = analogAxis;
|
2016-11-17 00:12:59 +00:00
|
|
|
|
|
|
|
gVRGripperPos = trTotal.getOrigin();
|
|
|
|
gVRGripperOrn = trTotal.getRotation();
|
2016-09-09 21:30:37 +00:00
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
2016-10-04 15:53:59 +00:00
|
|
|
gVRGripper2Analog = analogAxis;
|
2016-11-17 00:12:59 +00:00
|
|
|
gVRController2Pos = trTotal.getOrigin();
|
|
|
|
gVRController2Orn = trTotal.getRotation();
|
2016-09-23 02:48:26 +00:00
|
|
|
|
2016-11-17 00:12:59 +00:00
|
|
|
m_args[0].m_vrControllerPos[controllerId] = trTotal.getOrigin();
|
|
|
|
m_args[0].m_vrControllerOrn[controllerId] = trTotal.getRotation();
|
2016-09-09 21:30:37 +00:00
|
|
|
}
|
2016-09-08 22:15:58 +00:00
|
|
|
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->lock();
|
2016-12-27 03:40:09 +00:00
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
|
|
|
|
m_args[0].m_vrControllerEvents[controllerId].m_analogAxis = analogAxis;
|
2016-12-29 05:51:54 +00:00
|
|
|
m_args[0].m_csGUI->unlock();
|
2016-12-27 03:40:09 +00:00
|
|
|
|
2016-07-18 06:50:11 +00:00
|
|
|
}
|
|
|
|
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)
|