PhysicsServerExample.cpp 35 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334
  1. //todo(erwincoumans): re-use the upcoming b3RobotSimAPI here
  2. #include "PhysicsServerExample.h"
  3. #include "PhysicsServerSharedMemory.h"
  4. #include "Bullet3Common/b3CommandLineArgs.h"
  5. #include "SharedMemoryCommon.h"
  6. #include "Bullet3Common/b3Matrix3x3.h"
  7. #include "../Utils/b3Clock.h"
  8. #include "../MultiThreading/b3ThreadSupportInterface.h"
  9. #ifdef BT_ENABLE_VR
  10. #include "../RenderingExamples/TinyVRGui.h"
  11. #endif//BT_ENABLE_VR
  12. #include "../CommonInterfaces/CommonParameterInterface.h"
  13. #define MAX_VR_CONTROLLERS 8
  14. //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
  15. extern btVector3 gLastPickPos;
  16. btVector3 gVRTeleportPos(0,0,0);
  17. btQuaternion gVRTeleportOrn(0, 0, 0,1);
  18. extern btVector3 gVRGripperPos;
  19. extern btQuaternion gVRGripperOrn;
  20. extern btVector3 gVRController2Pos;
  21. extern btQuaternion gVRController2Orn;
  22. extern btScalar gVRGripperAnalog;
  23. extern btScalar gVRGripper2Analog;
  24. extern bool gCloseToKuka;
  25. extern bool gEnableRealTimeSimVR;
  26. extern bool gCreateSamuraiRobotAssets;
  27. extern int gCreateObjectSimVR;
  28. static int gGraspingController = -1;
  29. extern btScalar simTimeScalingFactor;
  30. extern bool gVRGripperClosed;
  31. bool gDebugRenderToggle = false;
  32. void MotionThreadFunc(void* userPtr,void* lsMemory);
  33. void* MotionlsMemoryFunc();
  34. #define MAX_MOTION_NUM_THREADS 1
  35. enum
  36. {
  37. numCubesX = 20,
  38. numCubesY = 20
  39. };
  40. enum TestExampleBrowserCommunicationEnums
  41. {
  42. eRequestTerminateMotion= 13,
  43. eMotionIsUnInitialized,
  44. eMotionIsInitialized,
  45. eMotionInitializationFailed,
  46. eMotionHasTerminated
  47. };
  48. enum MultiThreadedGUIHelperCommunicationEnums
  49. {
  50. eGUIHelperIdle= 13,
  51. eGUIHelperRegisterTexture,
  52. eGUIHelperRegisterGraphicsShape,
  53. eGUIHelperRegisterGraphicsInstance,
  54. eGUIHelperCreateCollisionShapeGraphicsObject,
  55. eGUIHelperCreateCollisionObjectGraphicsObject,
  56. eGUIHelperCreateRigidBodyGraphicsObject,
  57. eGUIHelperRemoveAllGraphicsInstances,
  58. eGUIHelperCopyCameraImageData,
  59. };
  60. #include <stdio.h>
  61. //#include "BulletMultiThreaded/PlatformDefinitions.h"
  62. #ifndef _WIN32
  63. #include "../MultiThreading/b3PosixThreadSupport.h"
  64. b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
  65. {
  66. b3PosixThreadSupport::ThreadConstructionInfo constructionInfo("MotionThreads",
  67. MotionThreadFunc,
  68. MotionlsMemoryFunc,
  69. numThreads);
  70. b3ThreadSupportInterface* threadSupport = new b3PosixThreadSupport(constructionInfo);
  71. return threadSupport;
  72. }
  73. #elif defined( _WIN32)
  74. #include "../MultiThreading/b3Win32ThreadSupport.h"
  75. b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
  76. {
  77. b3Win32ThreadSupport::Win32ThreadConstructionInfo threadConstructionInfo("MotionThreads",MotionThreadFunc,MotionlsMemoryFunc,numThreads);
  78. b3Win32ThreadSupport* threadSupport = new b3Win32ThreadSupport(threadConstructionInfo);
  79. return threadSupport;
  80. }
  81. #endif
  82. struct MotionArgs
  83. {
  84. MotionArgs()
  85. :m_physicsServerPtr(0)
  86. {
  87. for (int i=0;i<MAX_VR_CONTROLLERS;i++)
  88. {
  89. m_isVrControllerPicking[i] = false;
  90. m_isVrControllerDragging[i] = false;
  91. m_isVrControllerReleasing[i] = false;
  92. m_isVrControllerTeleporting[i] = false;
  93. }
  94. }
  95. b3CriticalSection* m_cs;
  96. PhysicsServerSharedMemory* m_physicsServerPtr;
  97. b3AlignedObjectArray<b3Vector3> m_positions;
  98. btVector3 m_vrControllerPos[MAX_VR_CONTROLLERS];
  99. btQuaternion m_vrControllerOrn[MAX_VR_CONTROLLERS];
  100. bool m_isVrControllerPicking[MAX_VR_CONTROLLERS];
  101. bool m_isVrControllerDragging[MAX_VR_CONTROLLERS];
  102. bool m_isVrControllerReleasing[MAX_VR_CONTROLLERS];
  103. bool m_isVrControllerTeleporting[MAX_VR_CONTROLLERS];
  104. };
  105. struct MotionThreadLocalStorage
  106. {
  107. int threadId;
  108. };
  109. int skip = 0;
  110. int skip1 = 0;
  111. float clampedDeltaTime = 0.2;
  112. void MotionThreadFunc(void* userPtr,void* lsMemory)
  113. {
  114. printf("MotionThreadFunc thread started\n");
  115. MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory;
  116. MotionArgs* args = (MotionArgs*) userPtr;
  117. int workLeft = true;
  118. b3Clock clock;
  119. clock.reset();
  120. bool init = true;
  121. if (init)
  122. {
  123. args->m_cs->lock();
  124. args->m_cs->setSharedParam(0,eMotionIsInitialized);
  125. args->m_cs->unlock();
  126. double deltaTimeInSeconds = 0;
  127. do
  128. {
  129. deltaTimeInSeconds+= double(clock.getTimeMicroseconds())/1000000.;
  130. if (deltaTimeInSeconds<(1./5000.))
  131. {
  132. skip++;
  133. skip1++;
  134. if (skip1>5)
  135. {
  136. b3Clock::usleep(250);
  137. }
  138. } else
  139. {
  140. skip1=0;
  141. //process special controller commands, such as
  142. //VR controller button press/release and controller motion
  143. for (int c=0;c<MAX_VR_CONTROLLERS;c++)
  144. {
  145. btVector3 from = args->m_vrControllerPos[c];
  146. btMatrix3x3 mat(args->m_vrControllerOrn[c]);
  147. btScalar pickDistance = 1000.;
  148. btVector3 toX = from+mat.getColumn(0);
  149. btVector3 toY = from+mat.getColumn(1);
  150. btVector3 toZ = from+mat.getColumn(2)*pickDistance;
  151. if (args->m_isVrControllerTeleporting[c])
  152. {
  153. args->m_isVrControllerTeleporting[c] = false;
  154. args->m_physicsServerPtr->pickBody(from,-toZ);
  155. args->m_physicsServerPtr->removePickingConstraint();
  156. }
  157. if (!gCloseToKuka)
  158. {
  159. if (args->m_isVrControllerPicking[c])
  160. {
  161. args->m_isVrControllerPicking[c] = false;
  162. args->m_isVrControllerDragging[c] = true;
  163. args->m_physicsServerPtr->pickBody(from,-toZ);
  164. //printf("PICK!\n");
  165. }
  166. }
  167. if (args->m_isVrControllerDragging[c])
  168. {
  169. args->m_physicsServerPtr->movePickedBody(from,-toZ);
  170. // printf(".");
  171. }
  172. if (args->m_isVrControllerReleasing[c])
  173. {
  174. args->m_isVrControllerDragging[c] = false;
  175. args->m_isVrControllerReleasing[c] = false;
  176. args->m_physicsServerPtr->removePickingConstraint();
  177. //printf("Release pick\n");
  178. }
  179. }
  180. //don't simulate over a huge timestep if we had some interruption (debugger breakpoint etc)
  181. if (deltaTimeInSeconds>clampedDeltaTime)
  182. {
  183. deltaTimeInSeconds = clampedDeltaTime;
  184. b3Warning("Clamp deltaTime from %f to %f",deltaTimeInSeconds, clampedDeltaTime);
  185. }
  186. clock.reset();
  187. args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds);
  188. deltaTimeInSeconds = 0;
  189. }
  190. args->m_physicsServerPtr->processClientCommands();
  191. } while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);
  192. } else
  193. {
  194. args->m_cs->lock();
  195. args->m_cs->setSharedParam(0,eMotionInitializationFailed);
  196. args->m_cs->unlock();
  197. }
  198. printf("finished, #skip = %d, skip1 = %d\n",skip,skip1);
  199. skip=0;
  200. skip1=0;
  201. //do nothing
  202. }
  203. void* MotionlsMemoryFunc()
  204. {
  205. //don't create local store memory, just return 0
  206. return new MotionThreadLocalStorage;
  207. }
  208. class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
  209. {
  210. CommonGraphicsApp* m_app;
  211. b3CriticalSection* m_cs;
  212. public:
  213. GUIHelperInterface* m_childGuiHelper;
  214. const unsigned char* m_texels;
  215. int m_textureWidth;
  216. int m_textureHeight;
  217. int m_shapeIndex;
  218. const float* m_position;
  219. const float* m_quaternion;
  220. const float* m_color;
  221. const float* m_scaling;
  222. const float* m_vertices;
  223. int m_numvertices;
  224. const int* m_indices;
  225. int m_numIndices;
  226. int m_primitiveType;
  227. int m_textureId;
  228. int m_instanceId;
  229. MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
  230. :m_app(app)
  231. ,m_cs(0),
  232. m_texels(0),
  233. m_textureId(-1)
  234. {
  235. m_childGuiHelper = guiHelper;;
  236. }
  237. virtual ~MultiThreadedOpenGLGuiHelper()
  238. {
  239. delete m_childGuiHelper;
  240. }
  241. void setCriticalSection(b3CriticalSection* cs)
  242. {
  243. m_cs = cs;
  244. }
  245. b3CriticalSection* getCriticalSection()
  246. {
  247. return m_cs;
  248. }
  249. btRigidBody* m_body;
  250. btVector3 m_color3;
  251. virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color)
  252. {
  253. m_body = body;
  254. m_color3 = color;
  255. m_cs->lock();
  256. m_cs->setSharedParam(1,eGUIHelperCreateRigidBodyGraphicsObject);
  257. m_cs->unlock();
  258. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  259. {
  260. b3Clock::usleep(1000);
  261. }
  262. }
  263. btCollisionObject* m_obj;
  264. btVector3 m_color2;
  265. virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj,const btVector3& color)
  266. {
  267. m_obj = obj;
  268. m_color2 = color;
  269. m_cs->lock();
  270. m_cs->setSharedParam(1,eGUIHelperCreateCollisionObjectGraphicsObject);
  271. m_cs->unlock();
  272. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  273. {
  274. b3Clock::usleep(1000);
  275. }
  276. }
  277. btCollisionShape* m_colShape;
  278. virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
  279. {
  280. m_colShape = collisionShape;
  281. m_cs->lock();
  282. m_cs->setSharedParam(1,eGUIHelperCreateCollisionShapeGraphicsObject);
  283. m_cs->unlock();
  284. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  285. {
  286. b3Clock::usleep(1000);
  287. }
  288. }
  289. virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld)
  290. {
  291. //this check is to prevent a crash, in case we removed all graphics instances, but there are still physics objects.
  292. //the check will be obsolete, once we have a better/safer way of synchronizing physics->graphics transforms
  293. if ( m_childGuiHelper->getRenderInterface()->getTotalNumInstances()>0)
  294. {
  295. m_childGuiHelper->syncPhysicsToGraphics(rbWorld);
  296. }
  297. }
  298. virtual void render(const btDiscreteDynamicsWorld* rbWorld)
  299. {
  300. m_childGuiHelper->render(0);
  301. }
  302. virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld)
  303. {
  304. m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
  305. }
  306. virtual int registerTexture(const unsigned char* texels, int width, int height)
  307. {
  308. m_texels = texels;
  309. m_textureWidth = width;
  310. m_textureHeight = height;
  311. m_cs->lock();
  312. m_cs->setSharedParam(1,eGUIHelperRegisterTexture);
  313. m_cs->unlock();
  314. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  315. {
  316. b3Clock::usleep(1000);
  317. }
  318. return m_textureId;
  319. }
  320. virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId)
  321. {
  322. m_vertices = vertices;
  323. m_numvertices = numvertices;
  324. m_indices = indices;
  325. m_numIndices = numIndices;
  326. m_primitiveType = primitiveType;
  327. m_textureId = textureId;
  328. m_cs->lock();
  329. m_cs->setSharedParam(1,eGUIHelperRegisterGraphicsShape);
  330. m_cs->unlock();
  331. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  332. {
  333. b3Clock::usleep(1000);
  334. }
  335. return m_shapeIndex;
  336. }
  337. virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
  338. {
  339. m_shapeIndex = shapeIndex;
  340. m_position = position;
  341. m_quaternion = quaternion;
  342. m_color = color;
  343. m_scaling = scaling;
  344. m_cs->lock();
  345. m_cs->setSharedParam(1,eGUIHelperRegisterGraphicsInstance);
  346. m_cs->unlock();
  347. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  348. {
  349. b3Clock::usleep(1000);
  350. }
  351. return m_instanceId;
  352. }
  353. virtual void removeAllGraphicsInstances()
  354. {
  355. m_cs->lock();
  356. m_cs->setSharedParam(1,eGUIHelperRemoveAllGraphicsInstances);
  357. m_cs->unlock();
  358. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  359. {
  360. b3Clock::usleep(1000);
  361. }
  362. }
  363. virtual Common2dCanvasInterface* get2dCanvasInterface()
  364. {
  365. return 0;
  366. }
  367. virtual CommonParameterInterface* getParameterInterface()
  368. {
  369. return 0;
  370. }
  371. virtual CommonRenderInterface* getRenderInterface()
  372. {
  373. return 0;
  374. }
  375. virtual CommonGraphicsApp* getAppInterface()
  376. {
  377. return m_childGuiHelper->getAppInterface();
  378. }
  379. virtual void setUpAxis(int axis)
  380. {
  381. m_childGuiHelper->setUpAxis(axis);
  382. }
  383. virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
  384. {
  385. m_childGuiHelper->resetCamera(camDist,pitch,yaw,camPosX,camPosY,camPosZ);
  386. }
  387. float m_viewMatrix[16];
  388. float m_projectionMatrix[16];
  389. unsigned char* m_pixelsRGBA;
  390. int m_rgbaBufferSizeInPixels;
  391. float* m_depthBuffer;
  392. int m_depthBufferSizeInPixels;
  393. int* m_segmentationMaskBuffer;
  394. int m_segmentationMaskBufferSizeInPixels;
  395. int m_startPixelIndex;
  396. int m_destinationWidth;
  397. int m_destinationHeight;
  398. int* m_numPixelsCopied;
  399. virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
  400. unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
  401. float* depthBuffer, int depthBufferSizeInPixels,
  402. int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels,
  403. int startPixelIndex, int destinationWidth,
  404. int destinationHeight, int* numPixelsCopied)
  405. {
  406. m_cs->lock();
  407. for (int i=0;i<16;i++)
  408. {
  409. m_viewMatrix[i] = viewMatrix[i];
  410. m_projectionMatrix[i] = projectionMatrix[i];
  411. }
  412. m_pixelsRGBA = pixelsRGBA;
  413. m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
  414. m_depthBuffer = depthBuffer;
  415. m_depthBufferSizeInPixels = depthBufferSizeInPixels;
  416. m_segmentationMaskBuffer = segmentationMaskBuffer;
  417. m_segmentationMaskBufferSizeInPixels = segmentationMaskBufferSizeInPixels;
  418. m_startPixelIndex = startPixelIndex;
  419. m_destinationWidth = destinationWidth;
  420. m_destinationHeight = destinationHeight;
  421. m_numPixelsCopied = numPixelsCopied;
  422. m_cs->setSharedParam(1,eGUIHelperCopyCameraImageData);
  423. m_cs->unlock();
  424. while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
  425. {
  426. b3Clock::usleep(1000);
  427. }
  428. }
  429. virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
  430. {
  431. }
  432. virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)
  433. {
  434. }
  435. };
  436. class PhysicsServerExample : public SharedMemoryCommon
  437. {
  438. PhysicsServerSharedMemory m_physicsServer;
  439. b3ThreadSupportInterface* m_threadSupport;
  440. MotionArgs m_args[MAX_MOTION_NUM_THREADS];
  441. MultiThreadedOpenGLGuiHelper* m_multiThreadedHelper;
  442. bool m_wantsShutdown;
  443. bool m_isConnected;
  444. btClock m_clock;
  445. bool m_replay;
  446. int m_options;
  447. #ifdef BT_ENABLE_VR
  448. TinyVRGui* m_tinyVrGui;
  449. #endif
  450. public:
  451. PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0);
  452. virtual ~PhysicsServerExample();
  453. virtual void initPhysics();
  454. virtual void stepSimulation(float deltaTime);
  455. void enableCommandLogging()
  456. {
  457. m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
  458. }
  459. void replayFromLogFile()
  460. {
  461. m_replay = true;
  462. m_physicsServer.replayFromLogFile("BulletPhysicsCommandLog.bin");
  463. }
  464. virtual void resetCamera()
  465. {
  466. float dist = 5;
  467. float pitch = 50;
  468. float yaw = 35;
  469. float targetPos[3]={0,0,0};//-3,2.8,-2.5};
  470. m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
  471. }
  472. virtual bool wantsTermination();
  473. virtual bool isConnected();
  474. virtual void renderScene();
  475. virtual void exitPhysics();
  476. virtual void physicsDebugDraw(int debugFlags);
  477. btVector3 getRayTo(int x,int y);
  478. virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]);
  479. virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis);
  480. virtual bool mouseMoveCallback(float x,float y)
  481. {
  482. if (m_replay)
  483. return false;
  484. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  485. if (!renderer)
  486. {
  487. return false;
  488. }
  489. btVector3 rayTo = getRayTo(int(x), int(y));
  490. btVector3 rayFrom;
  491. renderer->getActiveCamera()->getCameraPosition(rayFrom);
  492. m_physicsServer.movePickedBody(rayFrom,rayTo);
  493. return false;
  494. };
  495. virtual bool mouseButtonCallback(int button, int state, float x, float y)
  496. {
  497. if (m_replay)
  498. return false;
  499. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  500. if (!renderer)
  501. {
  502. return false;
  503. }
  504. CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
  505. if (state==1)
  506. {
  507. if(button==0 && (!window->isModifierKeyPressed(B3G_ALT) && !window->isModifierKeyPressed(B3G_CONTROL) ))
  508. {
  509. btVector3 camPos;
  510. renderer->getActiveCamera()->getCameraPosition(camPos);
  511. btVector3 rayFrom = camPos;
  512. btVector3 rayTo = getRayTo(int(x),int(y));
  513. m_physicsServer.pickBody(rayFrom, rayTo);
  514. }
  515. } else
  516. {
  517. if (button==0)
  518. {
  519. m_physicsServer.removePickingConstraint();
  520. //remove p2p
  521. }
  522. }
  523. //printf("button=%d, state=%d\n",button,state);
  524. return false;
  525. }
  526. virtual bool keyboardCallback(int key, int state){return false;}
  527. virtual void setSharedMemoryKey(int key)
  528. {
  529. m_physicsServer.setSharedMemoryKey(key);
  530. }
  531. virtual void processCommandLineArgs(int argc, char* argv[])
  532. {
  533. b3CommandLineArgs args(argc,argv);
  534. if (args.CheckCmdLineFlag("emptyworld"))
  535. {
  536. gCreateSamuraiRobotAssets = false;
  537. }
  538. }
  539. };
  540. PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem, int options)
  541. :SharedMemoryCommon(helper),
  542. m_physicsServer(sharedMem),
  543. m_wantsShutdown(false),
  544. m_isConnected(false),
  545. m_replay(false),
  546. m_options(options)
  547. #ifdef BT_ENABLE_VR
  548. ,m_tinyVrGui(0)
  549. #endif
  550. {
  551. m_multiThreadedHelper = helper;
  552. b3Printf("Started PhysicsServer\n");
  553. }
  554. PhysicsServerExample::~PhysicsServerExample()
  555. {
  556. #ifdef BT_ENABLE_VR
  557. delete m_tinyVrGui;
  558. #endif
  559. bool deInitializeSharedMemory = true;
  560. m_physicsServer.disconnectSharedMemory(deInitializeSharedMemory);
  561. m_isConnected = false;
  562. }
  563. bool PhysicsServerExample::isConnected()
  564. {
  565. return m_isConnected;
  566. }
  567. void PhysicsServerExample::initPhysics()
  568. {
  569. ///for this testing we use Z-axis up
  570. int upAxis = 2;
  571. m_guiHelper->setUpAxis(upAxis);
  572. m_threadSupport = createMotionThreadSupport(MAX_MOTION_NUM_THREADS);
  573. for (int i=0;i<m_threadSupport->getNumTasks();i++)
  574. {
  575. MotionThreadLocalStorage* storage = (MotionThreadLocalStorage*) m_threadSupport->getThreadLocalMemory(i);
  576. b3Assert(storage);
  577. storage->threadId = i;
  578. //storage->m_sharedMem = data->m_sharedMem;
  579. }
  580. for (int w=0;w<MAX_MOTION_NUM_THREADS;w++)
  581. {
  582. m_args[w].m_cs = m_threadSupport->createCriticalSection();
  583. m_args[w].m_cs->setSharedParam(0,eMotionIsUnInitialized);
  584. int numMoving = 0;
  585. m_args[w].m_positions.resize(numMoving);
  586. m_args[w].m_physicsServerPtr = &m_physicsServer;
  587. int index = 0;
  588. m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*) &this->m_args[w], w);
  589. while (m_args[w].m_cs->getSharedParam(0)==eMotionIsUnInitialized)
  590. {
  591. b3Clock::usleep(1000);
  592. }
  593. }
  594. m_args[0].m_cs->setSharedParam(1,eGUIHelperIdle);
  595. m_multiThreadedHelper->setCriticalSection(m_args[0].m_cs);
  596. m_isConnected = m_physicsServer.connectSharedMemory( m_guiHelper);
  597. }
  598. void PhysicsServerExample::exitPhysics()
  599. {
  600. for (int i=0;i<MAX_MOTION_NUM_THREADS;i++)
  601. {
  602. m_args[i].m_cs->lock();
  603. m_args[i].m_cs->setSharedParam(0,eRequestTerminateMotion);
  604. m_args[i].m_cs->unlock();
  605. }
  606. int numActiveThreads = MAX_MOTION_NUM_THREADS;
  607. while (numActiveThreads)
  608. {
  609. int arg0,arg1;
  610. if (m_threadSupport->isTaskCompleted(&arg0,&arg1,0))
  611. {
  612. numActiveThreads--;
  613. printf("numActiveThreads = %d\n",numActiveThreads);
  614. } else
  615. {
  616. b3Clock::usleep(1000);
  617. }
  618. };
  619. printf("stopping threads\n");
  620. delete m_threadSupport;
  621. m_threadSupport = 0;
  622. //m_physicsServer.resetDynamicsWorld();
  623. }
  624. bool PhysicsServerExample::wantsTermination()
  625. {
  626. return m_wantsShutdown;
  627. }
  628. void PhysicsServerExample::stepSimulation(float deltaTime)
  629. {
  630. //this->m_physicsServer.processClientCommands();
  631. //check if any graphics related tasks are requested
  632. switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1))
  633. {
  634. case eGUIHelperCreateCollisionShapeGraphicsObject:
  635. {
  636. m_multiThreadedHelper->m_childGuiHelper->createCollisionShapeGraphicsObject(m_multiThreadedHelper->m_colShape);
  637. m_multiThreadedHelper->getCriticalSection()->lock();
  638. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  639. m_multiThreadedHelper->getCriticalSection()->unlock();
  640. break;
  641. }
  642. case eGUIHelperCreateCollisionObjectGraphicsObject:
  643. {
  644. m_multiThreadedHelper->m_childGuiHelper->createCollisionObjectGraphicsObject(m_multiThreadedHelper->m_obj,
  645. m_multiThreadedHelper->m_color2);
  646. m_multiThreadedHelper->getCriticalSection()->lock();
  647. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  648. m_multiThreadedHelper->getCriticalSection()->unlock();
  649. break;
  650. }
  651. case eGUIHelperCreateRigidBodyGraphicsObject:
  652. {
  653. m_multiThreadedHelper->m_childGuiHelper->createRigidBodyGraphicsObject(m_multiThreadedHelper->m_body,m_multiThreadedHelper->m_color3);
  654. m_multiThreadedHelper->getCriticalSection()->lock();
  655. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  656. m_multiThreadedHelper->getCriticalSection()->unlock();
  657. break;
  658. }
  659. case eGUIHelperRegisterTexture:
  660. {
  661. m_multiThreadedHelper->m_textureId = m_multiThreadedHelper->m_childGuiHelper->registerTexture(m_multiThreadedHelper->m_texels,
  662. m_multiThreadedHelper->m_textureWidth,m_multiThreadedHelper->m_textureHeight);
  663. m_multiThreadedHelper->getCriticalSection()->lock();
  664. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  665. m_multiThreadedHelper->getCriticalSection()->unlock();
  666. break;
  667. }
  668. case eGUIHelperRegisterGraphicsShape:
  669. {
  670. m_multiThreadedHelper->m_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape(
  671. m_multiThreadedHelper->m_vertices,
  672. m_multiThreadedHelper->m_numvertices,
  673. m_multiThreadedHelper->m_indices,
  674. m_multiThreadedHelper->m_numIndices,
  675. m_multiThreadedHelper->m_primitiveType,
  676. m_multiThreadedHelper->m_textureId);
  677. m_multiThreadedHelper->getCriticalSection()->lock();
  678. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  679. m_multiThreadedHelper->getCriticalSection()->unlock();
  680. break;
  681. }
  682. case eGUIHelperRegisterGraphicsInstance:
  683. {
  684. m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance(
  685. m_multiThreadedHelper->m_shapeIndex,
  686. m_multiThreadedHelper->m_position,
  687. m_multiThreadedHelper->m_quaternion,
  688. m_multiThreadedHelper->m_color,
  689. m_multiThreadedHelper->m_scaling);
  690. m_multiThreadedHelper->getCriticalSection()->lock();
  691. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  692. m_multiThreadedHelper->getCriticalSection()->unlock();
  693. break;
  694. }
  695. case eGUIHelperRemoveAllGraphicsInstances:
  696. {
  697. m_multiThreadedHelper->m_childGuiHelper->removeAllGraphicsInstances();
  698. int numRenderInstances = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
  699. b3Assert(numRenderInstances==0);
  700. m_multiThreadedHelper->getCriticalSection()->lock();
  701. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  702. m_multiThreadedHelper->getCriticalSection()->unlock();
  703. break;
  704. }
  705. case eGUIHelperCopyCameraImageData:
  706. {
  707. m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
  708. m_multiThreadedHelper->m_projectionMatrix,
  709. m_multiThreadedHelper->m_pixelsRGBA,
  710. m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
  711. m_multiThreadedHelper->m_depthBuffer,
  712. m_multiThreadedHelper->m_depthBufferSizeInPixels,
  713. m_multiThreadedHelper->m_segmentationMaskBuffer,
  714. m_multiThreadedHelper->m_segmentationMaskBufferSizeInPixels,
  715. m_multiThreadedHelper->m_startPixelIndex,
  716. m_multiThreadedHelper->m_destinationWidth,
  717. m_multiThreadedHelper->m_destinationHeight,
  718. m_multiThreadedHelper->m_numPixelsCopied);
  719. m_multiThreadedHelper->getCriticalSection()->lock();
  720. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperIdle);
  721. m_multiThreadedHelper->getCriticalSection()->unlock();
  722. break;
  723. }
  724. case eGUIHelperIdle:
  725. default:
  726. {
  727. }
  728. }
  729. #if 0
  730. if (m_options == PHYSICS_SERVER_USE_RTC_CLOCK)
  731. {
  732. btClock rtc;
  733. btScalar endTime = rtc.getTimeMilliseconds() + deltaTime*btScalar(800);
  734. while (rtc.getTimeMilliseconds()<endTime)
  735. {
  736. m_physicsServer.processClientCommands();
  737. }
  738. } else
  739. {
  740. //for (int i=0;i<10;i++)
  741. m_physicsServer.processClientCommands();
  742. }
  743. #endif
  744. {
  745. if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
  746. {
  747. m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->writeTransforms();
  748. }
  749. }
  750. }
  751. static float vrOffset[16]={1,0,0,0,
  752. 0,1,0,0,
  753. 0,0,1,0,
  754. 0,0,0,0};
  755. extern int gDroppedSimulationSteps;
  756. extern int gNumSteps;
  757. extern double gDtInSec;
  758. extern double gSubStep;
  759. void PhysicsServerExample::renderScene()
  760. {
  761. B3_PROFILE("PhysicsServerExample::RenderScene");
  762. static char line0[1024];
  763. static char line1[1024];
  764. if (gEnableRealTimeSimVR)
  765. {
  766. static int frameCount=0;
  767. static btScalar prevTime = m_clock.getTimeSeconds();
  768. frameCount++;
  769. static btScalar worseFps = 1000000;
  770. int numFrames = 200;
  771. static int count = 0;
  772. count++;
  773. if (0 == (count & 1))
  774. {
  775. btScalar curTime = m_clock.getTimeSeconds();
  776. btScalar fps = 1. / (curTime - prevTime);
  777. prevTime = curTime;
  778. if (fps < worseFps)
  779. {
  780. worseFps = fps;
  781. }
  782. if (count > numFrames)
  783. {
  784. count = 0;
  785. sprintf(line0, "fps:%f frame:%d", worseFps, frameCount / 2);
  786. sprintf(line1, "drop:%d tscale:%f dt:%f, substep %f)", gDroppedSimulationSteps, simTimeScalingFactor,gDtInSec, gSubStep);
  787. gDroppedSimulationSteps = 0;
  788. worseFps = 1000000;
  789. }
  790. }
  791. #ifdef BT_ENABLE_VR
  792. if (m_tinyVrGui==0)
  793. {
  794. ComboBoxParams comboParams;
  795. comboParams.m_comboboxId = 0;
  796. comboParams.m_numItems = 0;
  797. comboParams.m_startItem = 0;
  798. comboParams.m_callback = 0;//MyComboBoxCallback;
  799. comboParams.m_userPointer = 0;//this;
  800. m_tinyVrGui = new TinyVRGui(comboParams,this->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface());
  801. m_tinyVrGui->init();
  802. }
  803. if (m_tinyVrGui)
  804. {
  805. b3Transform tr;tr.setIdentity();
  806. tr.setOrigin(b3MakeVector3(gVRController2Pos[0],gVRController2Pos[1],gVRController2Pos[2]));
  807. tr.setRotation(b3Quaternion(gVRController2Orn[0],gVRController2Orn[1],gVRController2Orn[2],gVRController2Orn[3]));
  808. tr = tr*b3Transform(b3Quaternion(0,0,-SIMD_HALF_PI),b3MakeVector3(0,0,0));
  809. b3Scalar dt = 0.01;
  810. m_tinyVrGui->clearTextArea();
  811. m_tinyVrGui->grapicalPrintf(line0,0,0,0,0,0,255);
  812. m_tinyVrGui->grapicalPrintf(line1,0,16,255,255,255,255);
  813. m_tinyVrGui->tick(dt,tr);
  814. }
  815. #endif//BT_ENABLE_VR
  816. }
  817. ///debug rendering
  818. //m_args[0].m_cs->lock();
  819. //gVRTeleportPos[0] += 0.01;
  820. vrOffset[12]=-gVRTeleportPos[0];
  821. vrOffset[13]=-gVRTeleportPos[1];
  822. vrOffset[14]=-gVRTeleportPos[2];
  823. this->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->
  824. getActiveCamera()->setVRCameraOffsetTransform(vrOffset);
  825. m_physicsServer.renderScene();
  826. for (int i=0;i<MAX_VR_CONTROLLERS;i++)
  827. {
  828. if (m_args[0].m_isVrControllerPicking[i] || m_args[0].m_isVrControllerDragging[i])
  829. {
  830. btVector3 from = m_args[0].m_vrControllerPos[i];
  831. btMatrix3x3 mat(m_args[0].m_vrControllerOrn[i]);
  832. btVector3 toX = from+mat.getColumn(0);
  833. btVector3 toY = from+mat.getColumn(1);
  834. btVector3 toZ = from+mat.getColumn(2);
  835. int width = 2;
  836. btVector4 color;
  837. color=btVector4(1,0,0,1);
  838. m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toX,color,width);
  839. color=btVector4(0,1,0,1);
  840. m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toY,color,width);
  841. color=btVector4(0,0,1,1);
  842. m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toZ,color,width);
  843. }
  844. }
  845. if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
  846. {
  847. gEnableRealTimeSimVR = true;
  848. }
  849. if (gDebugRenderToggle)
  850. if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
  851. {
  852. B3_PROFILE("Draw Debug HUD");
  853. //some little experiment to add text/HUD to a VR camera (HTC Vive/Oculus Rift)
  854. float pos[4];
  855. m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraTargetPosition(pos);
  856. pos[0]+=gVRTeleportPos[0];
  857. pos[1]+=gVRTeleportPos[1];
  858. pos[2]+=gVRTeleportPos[2];
  859. btTransform viewTr;
  860. btScalar m[16];
  861. float mf[16];
  862. m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraViewMatrix(mf);
  863. for (int i=0;i<16;i++)
  864. {
  865. m[i] = mf[i];
  866. }
  867. m[12]=+gVRTeleportPos[0];
  868. m[13]=+gVRTeleportPos[1];
  869. m[14]=+gVRTeleportPos[2];
  870. viewTr.setFromOpenGLMatrix(m);
  871. btTransform viewTrInv = viewTr.inverse();
  872. btVector3 side = viewTrInv.getBasis().getColumn(0);
  873. btVector3 up = viewTrInv.getBasis().getColumn(1);
  874. btVector3 fwd = viewTrInv.getBasis().getColumn(2);
  875. float upMag = 0;
  876. float sideMag = 2.2;
  877. float fwdMag = -4;
  878. m_guiHelper->getAppInterface()->drawText3D(line0,pos[0]+upMag*up[0]-sideMag*side[0]+fwdMag*fwd[0],pos[1]+upMag*up[1]-sideMag*side[1]+fwdMag*fwd[1],pos[2]+upMag*up[2]-sideMag*side[2]+fwdMag*fwd[2],1);
  879. //btVector3 fwd = viewTrInv.getBasis().getColumn(2);
  880. up = viewTrInv.getBasis().getColumn(1);
  881. upMag = -0.3;
  882. m_guiHelper->getAppInterface()->drawText3D(line1,pos[0]+upMag*up[0]-sideMag*side[0]+fwdMag*fwd[0],pos[1]+upMag*up[1]-sideMag*side[1]+fwdMag*fwd[1],pos[2]+upMag*up[2]-sideMag*side[2]+fwdMag*fwd[2],1);
  883. }
  884. //m_args[0].m_cs->unlock();
  885. }
  886. void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
  887. {
  888. ///debug rendering
  889. m_physicsServer.physicsDebugDraw(debugDrawFlags);
  890. }
  891. btVector3 PhysicsServerExample::getRayTo(int x,int y)
  892. {
  893. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  894. if (!renderer)
  895. {
  896. btAssert(0);
  897. return btVector3(0,0,0);
  898. }
  899. float top = 1.f;
  900. float bottom = -1.f;
  901. float nearPlane = 1.f;
  902. float tanFov = (top-bottom)*0.5f / nearPlane;
  903. float fov = btScalar(2.0) * btAtan(tanFov);
  904. btVector3 camPos,camTarget;
  905. renderer->getActiveCamera()->getCameraPosition(camPos);
  906. renderer->getActiveCamera()->getCameraTargetPosition(camTarget);
  907. btVector3 rayFrom = camPos;
  908. btVector3 rayForward = (camTarget-camPos);
  909. rayForward.normalize();
  910. float farPlane = 10000.f;
  911. rayForward*= farPlane;
  912. btVector3 rightOffset;
  913. btVector3 cameraUp=btVector3(0,0,0);
  914. cameraUp[m_guiHelper->getAppInterface()->getUpAxis()]=1;
  915. btVector3 vertical = cameraUp;
  916. btVector3 hor;
  917. hor = rayForward.cross(vertical);
  918. hor.normalize();
  919. vertical = hor.cross(rayForward);
  920. vertical.normalize();
  921. float tanfov = tanf(0.5f*fov);
  922. hor *= 2.f * farPlane * tanfov;
  923. vertical *= 2.f * farPlane * tanfov;
  924. btScalar aspect;
  925. float width = float(renderer->getScreenWidth());
  926. float height = float (renderer->getScreenHeight());
  927. aspect = width / height;
  928. hor*=aspect;
  929. btVector3 rayToCenter = rayFrom + rayForward;
  930. btVector3 dHor = hor * 1.f/width;
  931. btVector3 dVert = vertical * 1.f/height;
  932. btVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical;
  933. rayTo += btScalar(x) * dHor;
  934. rayTo -= btScalar(y) * dVert;
  935. return rayTo;
  936. }
  937. extern int gSharedMemoryKey;
  938. class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOptions& options)
  939. {
  940. MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(),options.m_guiHelper);
  941. PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
  942. options.m_sharedMem,
  943. options.m_option);
  944. if (gSharedMemoryKey>=0)
  945. {
  946. example->setSharedMemoryKey(gSharedMemoryKey);
  947. }
  948. if (options.m_option & PHYSICS_SERVER_ENABLE_COMMAND_LOGGING)
  949. {
  950. example->enableCommandLogging();
  951. }
  952. if (options.m_option & PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG)
  953. {
  954. example->replayFromLogFile();
  955. }
  956. return example;
  957. }
  958. void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4])
  959. {
  960. //printf("controllerId %d, button=%d\n",controllerId, button);
  961. if (controllerId<0 || controllerId>=MAX_VR_CONTROLLERS)
  962. return;
  963. if (gGraspingController < 0)
  964. gGraspingController = controllerId;
  965. if (controllerId != gGraspingController)
  966. {
  967. if (button == 1 && state == 0)
  968. {
  969. gVRTeleportPos = gLastPickPos;
  970. }
  971. } else
  972. {
  973. if (button == 1)
  974. {
  975. if (state == 1)
  976. {
  977. gDebugRenderToggle = 1;
  978. } else
  979. {
  980. gDebugRenderToggle = 0;
  981. if (simTimeScalingFactor==0)
  982. {
  983. simTimeScalingFactor = 1;
  984. } else
  985. {
  986. if (simTimeScalingFactor==1)
  987. {
  988. simTimeScalingFactor = 0.25;
  989. }
  990. else
  991. {
  992. simTimeScalingFactor = 0;
  993. }
  994. }
  995. }
  996. } else
  997. {
  998. }
  999. }
  1000. if (button==32 && state==0)
  1001. {
  1002. gCreateObjectSimVR = 1;
  1003. }
  1004. if (button==1)
  1005. {
  1006. m_args[0].m_isVrControllerTeleporting[controllerId] = true;
  1007. }
  1008. if (controllerId == gGraspingController && (button == 33))
  1009. {
  1010. gVRGripperClosed =state;
  1011. }
  1012. else
  1013. {
  1014. if (button == 33)
  1015. {
  1016. m_args[0].m_isVrControllerPicking[controllerId] = (state != 0);
  1017. m_args[0].m_isVrControllerReleasing[controllerId] = (state == 0);
  1018. }
  1019. if ((button == 33) || (button == 1))
  1020. {
  1021. m_args[0].m_vrControllerPos[controllerId].setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
  1022. m_args[0].m_vrControllerOrn[controllerId].setValue(orn[0], orn[1], orn[2], orn[3]);
  1023. }
  1024. }
  1025. }
  1026. void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
  1027. {
  1028. gEnableRealTimeSimVR = true;
  1029. if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS)
  1030. {
  1031. printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
  1032. return;
  1033. }
  1034. if (controllerId == gGraspingController)
  1035. {
  1036. gVRGripperAnalog = analogAxis;
  1037. gVRGripperPos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
  1038. btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]);
  1039. gVRGripperOrn = orgOrn*btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI);
  1040. }
  1041. else
  1042. {
  1043. gVRGripper2Analog = analogAxis;
  1044. gVRController2Pos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
  1045. btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]);
  1046. gVRController2Orn = orgOrn*btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI);
  1047. m_args[0].m_vrControllerPos[controllerId].setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
  1048. m_args[0].m_vrControllerOrn[controllerId].setValue(orn[0], orn[1], orn[2], orn[3]);
  1049. }
  1050. }
  1051. B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)