PhysicsServerExample.cpp 103 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176317731783179318031813182318331843185318631873188318931903191319231933194319531963197319831993200320132023203320432053206320732083209321032113212321332143215321632173218321932203221322232233224322532263227322832293230323132323233323432353236323732383239324032413242324332443245324632473248324932503251325232533254325532563257325832593260326132623263326432653266326732683269327032713272327332743275327632773278327932803281328232833284328532863287328832893290329132923293329432953296329732983299330033013302330333043305330633073308330933103311331233133314331533163317331833193320332133223323332433253326332733283329333033313332333333343335333633373338333933403341334233433344334533463347334833493350335133523353335433553356335733583359336033613362336333643365336633673368336933703371337233733374337533763377337833793380338133823383338433853386338733883389339033913392339333943395339633973398339934003401340234033404340534063407340834093410341134123413341434153416341734183419342034213422342334243425342634273428342934303431343234333434343534363437343834393440344134423443344434453446344734483449345034513452345334543455345634573458345934603461346234633464346534663467346834693470347134723473347434753476347734783479348034813482348334843485348634873488348934903491349234933494349534963497349834993500350135023503350435053506350735083509351035113512351335143515351635173518351935203521352235233524352535263527352835293530353135323533353435353536353735383539354035413542354335443545354635473548354935503551355235533554355535563557355835593560356135623563356435653566356735683569357035713572357335743575357635773578357935803581358235833584358535863587358835893590
  1. //todo(erwincoumans): re-use the upcoming b3RobotSimAPI here
  2. #include "PhysicsServerExample.h"
  3. #include "../CommonInterfaces/Common2dCanvasInterface.h"
  4. #include "PhysicsServerSharedMemory.h"
  5. #include "Bullet3Common/b3CommandLineArgs.h"
  6. #include "SharedMemoryCommon.h"
  7. #include "Bullet3Common/b3Matrix3x3.h"
  8. #include "../Utils/b3Clock.h"
  9. #include "../MultiThreading/b3ThreadSupportInterface.h"
  10. #include "SharedMemoryPublic.h"
  11. //#define BT_ENABLE_VR
  12. #define SYNC_CAMERA_USING_GUI_CS
  13. #ifdef BT_ENABLE_VR
  14. #include "../RenderingExamples/TinyVRGui.h"
  15. #endif //BT_ENABLE_VR
  16. #include "../CommonInterfaces/CommonParameterInterface.h"
  17. #include "../Importers/ImportURDFDemo/urdfStringSplit.h"
  18. //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
  19. bool gEnablePicking = true;
  20. bool gEnableTeleporting = true;
  21. bool gEnableRendering = true;
  22. bool gActivedVRRealTimeSimulation = false;
  23. bool gEnableSyncPhysicsRendering = true;
  24. static int gCamVisualizerWidth = 228;
  25. static int gCamVisualizerHeight = 192;
  26. static bool gEnableDefaultKeyboardShortcuts = true;
  27. static bool gEnableDefaultMousePicking = true;
  28. btScalar gVRTeleportRotZ = 0;
  29. extern int gInternalSimFlags;
  30. extern bool gResetSimulation;
  31. int gGraspingController = -1;
  32. extern btScalar simTimeScalingFactor;
  33. bool gBatchUserDebugLines = true;
  34. const char* startFileNameVR = "0_VRDemoSettings.txt";
  35. #include <vector>
  36. static void loadCurrentSettingsVR(b3CommandLineArgs& args)
  37. {
  38. //int currentEntry = 0;
  39. FILE* f = fopen(startFileNameVR, "r");
  40. if (f)
  41. {
  42. char oneline[1024];
  43. char* argv[] = {0, &oneline[0]};
  44. while (fgets(oneline, 1024, f) != NULL)
  45. {
  46. char* pos;
  47. if ((pos = strchr(oneline, '\n')) != NULL)
  48. *pos = '\0';
  49. args.addArgs(2, argv);
  50. }
  51. fclose(f);
  52. }
  53. };
  54. //remember the settings (you don't want to re-tune again and again...)
  55. static void saveCurrentSettingsVR(const btVector3& VRTeleportPos1)
  56. {
  57. FILE* f = fopen(startFileNameVR, "w");
  58. if (f)
  59. {
  60. fprintf(f, "--camPosX= %f\n", VRTeleportPos1[0]);
  61. fprintf(f, "--camPosY= %f\n", VRTeleportPos1[1]);
  62. fprintf(f, "--camPosZ= %f\n", VRTeleportPos1[2]);
  63. fprintf(f, "--camRotZ= %f\n", gVRTeleportRotZ);
  64. fclose(f);
  65. }
  66. };
  67. bool gDebugRenderToggle = false;
  68. void MotionThreadFunc(void* userPtr, void* lsMemory);
  69. void* MotionlsMemoryFunc();
  70. void MotionlsMemoryReleaseFunc(void* ptr);
  71. #define MAX_MOTION_NUM_THREADS 1
  72. enum
  73. {
  74. numCubesX = 20,
  75. numCubesY = 20
  76. };
  77. enum TestExampleBrowserCommunicationEnums
  78. {
  79. eRequestTerminateMotion = 13,
  80. eMotionIsUnInitialized,
  81. eMotionIsInitialized,
  82. eMotionInitializationFailed,
  83. eMotionHasTerminated
  84. };
  85. enum MultiThreadedGUIHelperCommunicationEnums
  86. {
  87. eGUIHelperIdle = 13,
  88. eGUIHelperRegisterTexture,
  89. eGUIHelperRegisterGraphicsShape,
  90. eGUIHelperRegisterGraphicsInstance,
  91. eGUIHelperCreateCollisionShapeGraphicsObject,
  92. eGUIHelperCreateCollisionObjectGraphicsObject,
  93. eGUIHelperCreateRigidBodyGraphicsObject,
  94. eGUIHelperRemoveAllGraphicsInstances,
  95. eGUIHelperCopyCameraImageData,
  96. eGUIHelperDisplayCameraImageData,
  97. eGUIHelperAutogenerateGraphicsObjects,
  98. eGUIUserDebugAddText,
  99. eGUIUserDebugAddLine,
  100. eGUIUserDebugAddParameter,
  101. eGUIUserDebugRemoveItem,
  102. eGUIUserDebugRemoveAllItems,
  103. eGUIDumpFramesToVideo,
  104. eGUIHelperRemoveGraphicsInstance,
  105. eGUIHelperChangeGraphicsInstanceRGBAColor,
  106. eGUIHelperChangeGraphicsInstanceSpecularColor,
  107. eGUIHelperSetVisualizerFlag,
  108. eGUIHelperChangeGraphicsInstanceTextureId,
  109. eGUIHelperGetShapeIndexFromInstance,
  110. eGUIHelperChangeTexture,
  111. eGUIHelperRemoveTexture,
  112. eGUIHelperSetVisualizerFlagCheckRenderedFrame,
  113. eGUIHelperUpdateShape,
  114. eGUIHelperChangeGraphicsInstanceScaling,
  115. eGUIUserDebugRemoveAllParameters,
  116. eGUIHelperResetCamera,
  117. eGUIHelperChangeGraphicsInstanceFlags,
  118. eGUIHelperSetRgbBackground,
  119. eGUIUserDebugAddPoints,
  120. };
  121. #include <stdio.h>
  122. //#include "BulletMultiThreaded/PlatformDefinitions.h"
  123. #ifndef _WIN32
  124. #include "../MultiThreading/b3PosixThreadSupport.h"
  125. b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
  126. {
  127. b3PosixThreadSupport::ThreadConstructionInfo constructionInfo("MotionThreads",
  128. MotionThreadFunc,
  129. MotionlsMemoryFunc,
  130. MotionlsMemoryReleaseFunc,
  131. numThreads);
  132. b3ThreadSupportInterface* threadSupport = new b3PosixThreadSupport(constructionInfo);
  133. return threadSupport;
  134. }
  135. #elif defined(_WIN32)
  136. #include "../MultiThreading/b3Win32ThreadSupport.h"
  137. b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
  138. {
  139. b3Win32ThreadSupport::Win32ThreadConstructionInfo threadConstructionInfo("MotionThreads", MotionThreadFunc, MotionlsMemoryFunc, MotionlsMemoryReleaseFunc, numThreads);
  140. b3Win32ThreadSupport* threadSupport = new b3Win32ThreadSupport(threadConstructionInfo);
  141. return threadSupport;
  142. }
  143. #endif
  144. enum MyMouseCommandType
  145. {
  146. MyMouseMove = 1,
  147. MyMouseButtonDown,
  148. MyMouseButtonUp
  149. };
  150. struct MyMouseCommand
  151. {
  152. btVector3 m_rayFrom;
  153. btVector3 m_rayTo;
  154. int m_type;
  155. };
  156. struct MotionArgs
  157. {
  158. MotionArgs()
  159. : m_debugDrawFlags(0),
  160. m_enableUpdateDebugDrawLines(true),
  161. m_physicsServerPtr(0)
  162. {
  163. for (int i = 0; i < MAX_VR_CONTROLLERS; i++)
  164. {
  165. m_vrControllerEvents[i].m_numButtonEvents = 0;
  166. m_vrControllerEvents[i].m_numMoveEvents = 0;
  167. for (int b = 0; b < MAX_VR_BUTTONS; b++)
  168. {
  169. m_vrControllerEvents[i].m_buttons[b] = 0;
  170. }
  171. m_vrControllerPos[i].setValue(0, 0, 0);
  172. m_vrControllerOrn[i].setValue(0, 0, 0, 1);
  173. m_isVrControllerPicking[i] = false;
  174. m_isVrControllerDragging[i] = false;
  175. m_isVrControllerReleasing[i] = false;
  176. m_isVrControllerTeleporting[i] = false;
  177. }
  178. }
  179. b3CriticalSection* m_cs;
  180. b3CriticalSection* m_cs2;
  181. b3CriticalSection* m_cs3;
  182. b3CriticalSection* m_csGUI;
  183. int m_debugDrawFlags;
  184. bool m_enableUpdateDebugDrawLines;
  185. btAlignedObjectArray<MyMouseCommand> m_mouseCommands;
  186. b3VRControllerEvent m_vrControllerEvents[MAX_VR_CONTROLLERS];
  187. b3VRControllerEvent m_sendVrControllerEvents[MAX_VR_CONTROLLERS];
  188. btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
  189. btAlignedObjectArray<b3KeyboardEvent> m_sendKeyEvents;
  190. btAlignedObjectArray<b3MouseEvent> m_allMouseEvents;
  191. btAlignedObjectArray<b3MouseEvent> m_sendMouseEvents;
  192. PhysicsServerSharedMemory* m_physicsServerPtr;
  193. b3AlignedObjectArray<b3Vector3> m_positions;
  194. btVector3 m_vrControllerPos[MAX_VR_CONTROLLERS];
  195. btQuaternion m_vrControllerOrn[MAX_VR_CONTROLLERS];
  196. bool m_isVrControllerPicking[MAX_VR_CONTROLLERS];
  197. bool m_isVrControllerDragging[MAX_VR_CONTROLLERS];
  198. bool m_isVrControllerReleasing[MAX_VR_CONTROLLERS];
  199. bool m_isVrControllerTeleporting[MAX_VR_CONTROLLERS];
  200. };
  201. struct MotionThreadLocalStorage
  202. {
  203. int threadId;
  204. };
  205. float clampedDeltaTime = 0.2;
  206. void MotionThreadFunc(void* userPtr, void* lsMemory)
  207. {
  208. printf("MotionThreadFunc thread started\n");
  209. //MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory;
  210. MotionArgs* args = (MotionArgs*)userPtr;
  211. //int workLeft = true;
  212. b3Clock clock;
  213. clock.reset();
  214. b3Clock sleepClock;
  215. bool init = true;
  216. if (init)
  217. {
  218. unsigned int cachedSharedParam = eMotionIsInitialized;
  219. args->m_cs->lock();
  220. args->m_cs->setSharedParam(0, eMotionIsInitialized);
  221. args->m_cs->unlock();
  222. double deltaTimeInSeconds = 0;
  223. int numCmdSinceSleep1ms = 0;
  224. unsigned long long int prevTime = clock.getTimeMicroseconds();
  225. do
  226. {
  227. {
  228. b3Clock::usleep(0);
  229. }
  230. {
  231. if (sleepClock.getTimeMilliseconds() > 1)
  232. {
  233. sleepClock.reset();
  234. numCmdSinceSleep1ms = 0;
  235. }
  236. }
  237. unsigned long long int curTime = clock.getTimeMicroseconds();
  238. unsigned long long int dtMicro = curTime - prevTime;
  239. prevTime = curTime;
  240. #if 1
  241. double dt = double(dtMicro) / 1000000.;
  242. #else
  243. double dt = double(clock.getTimeMicroseconds()) / 1000000.;
  244. clock.reset();
  245. #endif
  246. deltaTimeInSeconds += dt;
  247. {
  248. //process special controller commands, such as
  249. //VR controller button press/release and controller motion
  250. for (int c = 0; c < MAX_VR_CONTROLLERS; c++)
  251. {
  252. btVector3 from = args->m_vrControllerPos[c];
  253. btMatrix3x3 mat(args->m_vrControllerOrn[c]);
  254. btScalar pickDistance = 1000.;
  255. btVector3 to = from + mat.getColumn(0) * pickDistance;
  256. // btVector3 toY = from+mat.getColumn(1)*pickDistance;
  257. // btVector3 toZ = from+mat.getColumn(2)*pickDistance;
  258. if (args->m_isVrControllerTeleporting[c])
  259. {
  260. args->m_isVrControllerTeleporting[c] = false;
  261. args->m_physicsServerPtr->pickBody(from, to);
  262. args->m_physicsServerPtr->removePickingConstraint();
  263. }
  264. // if (!gEnableKukaControl)
  265. {
  266. if (args->m_isVrControllerPicking[c])
  267. {
  268. args->m_isVrControllerPicking[c] = false;
  269. args->m_isVrControllerDragging[c] = true;
  270. args->m_physicsServerPtr->pickBody(from, to);
  271. //printf("PICK!\n");
  272. }
  273. }
  274. if (args->m_isVrControllerDragging[c])
  275. {
  276. args->m_physicsServerPtr->movePickedBody(from, to);
  277. // printf(".");
  278. }
  279. if (args->m_isVrControllerReleasing[c])
  280. {
  281. args->m_isVrControllerDragging[c] = false;
  282. args->m_isVrControllerReleasing[c] = false;
  283. args->m_physicsServerPtr->removePickingConstraint();
  284. //printf("Release pick\n");
  285. }
  286. }
  287. //don't simulate over a huge timestep if we had some interruption (debugger breakpoint etc)
  288. if (deltaTimeInSeconds > clampedDeltaTime)
  289. {
  290. deltaTimeInSeconds = clampedDeltaTime;
  291. //b3Warning("Clamp deltaTime from %f to %f",deltaTimeInSeconds, clampedDeltaTime);
  292. }
  293. args->m_csGUI->lock();
  294. int numSendVrControllers = 0;
  295. for (int i = 0; i < MAX_VR_CONTROLLERS; i++)
  296. {
  297. if (args->m_vrControllerEvents[i].m_numButtonEvents + args->m_vrControllerEvents[i].m_numMoveEvents)
  298. {
  299. args->m_sendVrControllerEvents[numSendVrControllers++] =
  300. args->m_vrControllerEvents[i];
  301. if (args->m_vrControllerEvents[i].m_numButtonEvents)
  302. {
  303. for (int b = 0; b < MAX_VR_BUTTONS; b++)
  304. {
  305. args->m_vrControllerEvents[i].m_buttons[b] &= eButtonIsDown;
  306. }
  307. }
  308. args->m_vrControllerEvents[i].m_numMoveEvents = 0;
  309. args->m_vrControllerEvents[i].m_numButtonEvents = 0;
  310. }
  311. }
  312. args->m_sendKeyEvents.resize(args->m_keyboardEvents.size());
  313. for (int i = 0; i < args->m_keyboardEvents.size(); i++)
  314. {
  315. args->m_sendKeyEvents[i] = args->m_keyboardEvents[i];
  316. if (args->m_keyboardEvents[i].m_keyState & eButtonReleased)
  317. {
  318. args->m_keyboardEvents[i].m_keyState = 0;
  319. }
  320. else
  321. {
  322. args->m_keyboardEvents[i].m_keyState &= ~eButtonTriggered;
  323. }
  324. }
  325. //remove the 'released' events
  326. for (int i = args->m_keyboardEvents.size() - 1; i >= 0; i--)
  327. {
  328. if (args->m_keyboardEvents[i].m_keyState == 0)
  329. {
  330. args->m_keyboardEvents.removeAtIndex(i);
  331. }
  332. }
  333. b3KeyboardEvent* keyEvents = args->m_sendKeyEvents.size() ? &args->m_sendKeyEvents[0] : 0;
  334. args->m_csGUI->unlock();
  335. args->m_csGUI->lock();
  336. if (gEnableDefaultMousePicking)
  337. {
  338. for (int i = 0; i < args->m_mouseCommands.size(); i++)
  339. {
  340. switch (args->m_mouseCommands[i].m_type)
  341. {
  342. case MyMouseMove:
  343. {
  344. args->m_physicsServerPtr->movePickedBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
  345. break;
  346. };
  347. case MyMouseButtonDown:
  348. {
  349. args->m_physicsServerPtr->pickBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
  350. break;
  351. }
  352. case MyMouseButtonUp:
  353. {
  354. args->m_physicsServerPtr->removePickingConstraint();
  355. break;
  356. }
  357. default:
  358. {
  359. }
  360. }
  361. }
  362. }
  363. args->m_sendMouseEvents.resize(args->m_allMouseEvents.size());
  364. for (int i = 0; i < args->m_allMouseEvents.size(); i++)
  365. {
  366. args->m_sendMouseEvents[i] = args->m_allMouseEvents[i];
  367. }
  368. b3MouseEvent* mouseEvents = args->m_sendMouseEvents.size() ? &args->m_sendMouseEvents[0] : 0;
  369. args->m_allMouseEvents.clear();
  370. args->m_mouseCommands.clear();
  371. args->m_csGUI->unlock();
  372. {
  373. args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents, numSendVrControllers, keyEvents, args->m_sendKeyEvents.size(), mouseEvents, args->m_sendMouseEvents.size());
  374. }
  375. {
  376. args->m_csGUI->lock();
  377. if (args->m_enableUpdateDebugDrawLines)
  378. {
  379. args->m_physicsServerPtr->physicsDebugDraw(args->m_debugDrawFlags);
  380. args->m_enableUpdateDebugDrawLines = false;
  381. }
  382. args->m_csGUI->unlock();
  383. }
  384. deltaTimeInSeconds = 0;
  385. }
  386. {
  387. args->m_physicsServerPtr->processClientCommands();
  388. numCmdSinceSleep1ms++;
  389. }
  390. args->m_physicsServerPtr->reportNotifications();
  391. args->m_cs->lock();
  392. cachedSharedParam = args->m_cs->getSharedParam(0);
  393. args->m_cs->unlock();
  394. } while (cachedSharedParam != eRequestTerminateMotion);
  395. }
  396. else
  397. {
  398. args->m_cs->lock();
  399. args->m_cs->setSharedParam(0, eMotionInitializationFailed);
  400. args->m_cs->unlock();
  401. }
  402. args->m_physicsServerPtr->disconnectSharedMemory(true);
  403. //do nothing
  404. }
  405. void* MotionlsMemoryFunc()
  406. {
  407. //don't create local store memory, just return 0
  408. return new MotionThreadLocalStorage;
  409. }
  410. void MotionlsMemoryReleaseFunc(void* ptr)
  411. {
  412. MotionThreadLocalStorage* p = (MotionThreadLocalStorage*)ptr;
  413. delete p;
  414. }
  415. struct UserDebugDrawLine
  416. {
  417. double m_debugLineFromXYZ[3];
  418. double m_debugLineToXYZ[3];
  419. double m_debugLineColorRGB[3];
  420. double m_lineWidth;
  421. double m_lifeTime;
  422. int m_itemUniqueId;
  423. int m_trackingVisualShapeIndex;
  424. int m_replaceItemUid;
  425. };
  426. struct UserDebugDrawPoint
  427. {
  428. const double* m_debugPointPositions;
  429. const double* m_debugPointColors;
  430. int m_debugPointNum;
  431. double m_pointSize;
  432. double m_lifeTime;
  433. int m_itemUniqueId;
  434. int m_trackingVisualShapeIndex;
  435. int m_replaceItemUid;
  436. };
  437. struct UserDebugParameter
  438. {
  439. char m_text[1024];
  440. double m_rangeMin;
  441. double m_rangeMax;
  442. btScalar m_value;
  443. int m_itemUniqueId;
  444. };
  445. static void UserButtonToggle(int buttonId, bool buttonState, void* userPointer)
  446. {
  447. UserDebugParameter* param = (UserDebugParameter*)userPointer;
  448. param->m_value += 1;
  449. }
  450. struct UserDebugText
  451. {
  452. char m_text[1024];
  453. double m_textPositionXYZ1[3];
  454. double m_textColorRGB[3];
  455. double textSize;
  456. double m_lifeTime;
  457. int m_itemUniqueId;
  458. double m_textOrientation[4];
  459. int m_trackingVisualShapeIndex;
  460. int m_optionFlags;
  461. };
  462. struct LineSegment
  463. {
  464. btVector3 m_from;
  465. btVector3 m_to;
  466. };
  467. struct ColorWidth
  468. {
  469. btVector3FloatData m_color;
  470. int width;
  471. int getHash() const
  472. {
  473. unsigned char r = (unsigned char)m_color.m_floats[0] * 255;
  474. unsigned char g = (unsigned char)m_color.m_floats[1] * 255;
  475. unsigned char b = (unsigned char)m_color.m_floats[2] * 255;
  476. unsigned char w = width;
  477. return r + (256 * g) + (256 * 256 * b) + (256 * 256 * 256 * w);
  478. }
  479. bool equals(const ColorWidth& other) const
  480. {
  481. bool same = ((width == other.width) && (m_color.m_floats[0] == other.m_color.m_floats[0]) &&
  482. (m_color.m_floats[1] == other.m_color.m_floats[1]) &&
  483. (m_color.m_floats[2] == other.m_color.m_floats[2]));
  484. return same;
  485. }
  486. };
  487. ATTRIBUTE_ALIGNED16(class)
  488. MultithreadedDebugDrawer : public btIDebugDraw
  489. {
  490. struct GUIHelperInterface* m_guiHelper;
  491. int m_debugMode;
  492. btAlignedObjectArray<btAlignedObjectArray<unsigned int> > m_sortedIndices;
  493. btAlignedObjectArray<btAlignedObjectArray<btVector3FloatData> > m_sortedLines;
  494. btHashMap<ColorWidth, int> m_hashedLines;
  495. public:
  496. virtual void drawDebugDrawerLines()
  497. {
  498. if (m_hashedLines.size())
  499. {
  500. for (int i = 0; i < m_hashedLines.size(); i++)
  501. {
  502. ColorWidth cw = m_hashedLines.getKeyAtIndex(i);
  503. int index = *m_hashedLines.getAtIndex(i);
  504. int stride = sizeof(btVector3FloatData);
  505. const float* positions = &m_sortedLines[index][0].m_floats[0];
  506. int numPoints = m_sortedLines[index].size();
  507. const unsigned int* indices = &m_sortedIndices[index][0];
  508. int numIndices = m_sortedIndices[index].size();
  509. m_guiHelper->getRenderInterface()->drawLines(positions, cw.m_color.m_floats, numPoints, stride, indices, numIndices, cw.width);
  510. }
  511. }
  512. }
  513. MultithreadedDebugDrawer(GUIHelperInterface * guiHelper)
  514. : m_guiHelper(guiHelper),
  515. m_debugMode(0)
  516. {
  517. }
  518. virtual ~MultithreadedDebugDrawer()
  519. {
  520. }
  521. virtual void drawLine(const btVector3& from, const btVector3& to, const btVector3& color)
  522. {
  523. {
  524. ColorWidth cw;
  525. color.serializeFloat(cw.m_color);
  526. cw.width = 1;
  527. int index = -1;
  528. int* indexPtr = m_hashedLines.find(cw);
  529. if (indexPtr)
  530. {
  531. index = *indexPtr;
  532. }
  533. else
  534. {
  535. index = m_sortedLines.size();
  536. m_sortedLines.expand();
  537. m_sortedIndices.expand();
  538. m_hashedLines.insert(cw, index);
  539. }
  540. btAssert(index >= 0);
  541. if (index >= 0)
  542. {
  543. btVector3FloatData from1, toX1;
  544. m_sortedIndices[index].push_back(m_sortedLines[index].size());
  545. from.serializeFloat(from1);
  546. m_sortedLines[index].push_back(from1);
  547. m_sortedIndices[index].push_back(m_sortedLines[index].size());
  548. to.serializeFloat(toX1);
  549. m_sortedLines[index].push_back(toX1);
  550. }
  551. }
  552. }
  553. virtual void drawContactPoint(const btVector3& PointOnB, const btVector3& normalOnB, btScalar distance, int lifeTime, const btVector3& color)
  554. {
  555. drawLine(PointOnB, PointOnB + normalOnB * distance, color);
  556. btVector3 ncolor(0, 0, 0);
  557. drawLine(PointOnB, PointOnB + normalOnB * 0.01, ncolor);
  558. }
  559. virtual void reportErrorWarning(const char* warningString)
  560. {
  561. }
  562. virtual void draw3dText(const btVector3& location, const char* textString)
  563. {
  564. }
  565. virtual void setDebugMode(int debugMode)
  566. {
  567. m_debugMode = debugMode;
  568. }
  569. virtual int getDebugMode() const
  570. {
  571. return m_debugMode;
  572. }
  573. virtual void clearLines()
  574. {
  575. m_hashedLines.clear();
  576. m_sortedIndices.clear();
  577. m_sortedLines.clear();
  578. }
  579. virtual void flushLines()
  580. {
  581. }
  582. };
  583. class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
  584. {
  585. // CommonGraphicsApp* m_app;
  586. b3CriticalSection* m_cs;
  587. b3CriticalSection* m_cs2;
  588. b3CriticalSection* m_cs3;
  589. b3CriticalSection* m_csGUI;
  590. public:
  591. MultithreadedDebugDrawer* m_debugDraw;
  592. virtual void drawDebugDrawerLines()
  593. {
  594. if (m_debugDraw)
  595. {
  596. m_csGUI->lock();
  597. //draw stuff and flush?
  598. m_debugDraw->drawDebugDrawerLines();
  599. m_csGUI->unlock();
  600. }
  601. }
  602. virtual void clearLines()
  603. {
  604. m_csGUI->lock();
  605. if (m_debugDraw)
  606. {
  607. m_debugDraw->clearLines();
  608. }
  609. m_csGUI->unlock();
  610. }
  611. GUIHelperInterface* m_childGuiHelper;
  612. btHashMap<btHashPtr, int> m_cachedTextureIds;
  613. int m_uidGenerator;
  614. const unsigned char* m_texels;
  615. int m_textureWidth;
  616. int m_textureHeight;
  617. int m_shapeIndex;
  618. const float* m_position;
  619. const float* m_quaternion;
  620. const float* m_color;
  621. const float* m_scaling;
  622. const float* m_vertices;
  623. int m_numvertices;
  624. const int* m_indices;
  625. int m_numIndices;
  626. int m_primitiveType;
  627. int m_textureId;
  628. int m_instanceId;
  629. bool m_skipGraphicsUpdate;
  630. void mainThreadRelease()
  631. {
  632. BT_PROFILE("mainThreadRelease");
  633. setSharedParam(1, eGUIHelperIdle);
  634. getCriticalSection3()->lock();
  635. getCriticalSection2()->unlock();
  636. getCriticalSection()->lock();
  637. getCriticalSection2()->lock();
  638. getCriticalSection()->unlock();
  639. getCriticalSection3()->unlock();
  640. }
  641. void workerThreadWait()
  642. {
  643. BT_PROFILE("workerThreadWait");
  644. if (m_skipGraphicsUpdate)
  645. {
  646. this->m_csGUI->lock();
  647. getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
  648. this->m_csGUI->unlock();
  649. m_cs->unlock();
  650. return;
  651. }
  652. m_cs2->lock();
  653. m_cs->unlock();
  654. m_cs2->unlock();
  655. m_cs3->lock();
  656. m_cs3->unlock();
  657. m_csGUI->lock();
  658. unsigned int cachedSharedParam = m_cs->getSharedParam(1);
  659. m_csGUI->unlock();
  660. while (cachedSharedParam != eGUIHelperIdle)
  661. {
  662. b3Clock::usleep(0);
  663. m_csGUI->lock();
  664. cachedSharedParam = m_cs->getSharedParam(1);
  665. m_csGUI->unlock();
  666. }
  667. }
  668. MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper, int skipGraphicsUpdate)
  669. : //m_app(app),
  670. m_cs(0),
  671. m_cs2(0),
  672. m_cs3(0),
  673. m_csGUI(0),
  674. m_debugDraw(0),
  675. m_uidGenerator(0),
  676. m_texels(0),
  677. m_shapeIndex(-1),
  678. m_textureId(-1),
  679. m_instanceId(-1),
  680. m_skipGraphicsUpdate(skipGraphicsUpdate)
  681. {
  682. m_cameraUpdated = 0;
  683. m_childGuiHelper = guiHelper;
  684. }
  685. virtual ~MultiThreadedOpenGLGuiHelper()
  686. {
  687. //delete m_childGuiHelper;
  688. if (m_debugDraw)
  689. {
  690. delete m_debugDraw;
  691. m_debugDraw = 0;
  692. }
  693. for (int i = 0; i < m_userDebugParams.size(); i++)
  694. {
  695. delete m_userDebugParams[i];
  696. }
  697. m_userDebugParams.clear();
  698. }
  699. void setCriticalSection(b3CriticalSection* cs)
  700. {
  701. m_cs = cs;
  702. }
  703. b3CriticalSection* getCriticalSection()
  704. {
  705. return m_cs;
  706. }
  707. void setCriticalSection2(b3CriticalSection* cs)
  708. {
  709. m_cs2 = cs;
  710. }
  711. b3CriticalSection* getCriticalSection2()
  712. {
  713. return m_cs2;
  714. }
  715. void setCriticalSection3(b3CriticalSection* cs)
  716. {
  717. m_cs3 = cs;
  718. }
  719. void setCriticalSectionGUI(b3CriticalSection* cs)
  720. {
  721. m_csGUI = cs;
  722. }
  723. b3CriticalSection* getCriticalSection3()
  724. {
  725. return m_cs3;
  726. }
  727. b3CriticalSection* getCriticalSectionGUI()
  728. {
  729. return m_csGUI;
  730. }
  731. btRigidBody* m_body;
  732. btVector3 m_color3;
  733. virtual void createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color)
  734. {
  735. m_cs->lock();
  736. m_body = body;
  737. m_color3 = color;
  738. setSharedParam(1, eGUIHelperCreateRigidBodyGraphicsObject);
  739. workerThreadWait();
  740. }
  741. btCollisionObject* m_obj;
  742. btVector3 m_color2;
  743. virtual void createCollisionObjectGraphicsObject(btCollisionObject* obj, const btVector3& color)
  744. {
  745. m_cs->lock();
  746. m_obj = obj;
  747. m_color2 = color;
  748. setSharedParam(1, eGUIHelperCreateCollisionObjectGraphicsObject);
  749. workerThreadWait();
  750. }
  751. btCollisionShape* m_colShape;
  752. virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
  753. {
  754. m_cs->lock();
  755. m_colShape = collisionShape;
  756. setSharedParam(1, eGUIHelperCreateCollisionShapeGraphicsObject);
  757. workerThreadWait();
  758. }
  759. virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld)
  760. {
  761. //this check is to prevent a crash, in case we removed all graphics instances, but there are still physics objects.
  762. //the check will be obsolete, once we have a better/safer way of synchronizing physics->graphics transforms
  763. if (m_childGuiHelper->getRenderInterface() && m_childGuiHelper->getRenderInterface()->getTotalNumInstances() > 0)
  764. {
  765. m_childGuiHelper->syncPhysicsToGraphics(rbWorld);
  766. }
  767. }
  768. virtual void syncPhysicsToGraphics2(const btDiscreteDynamicsWorld* rbWorld)
  769. {
  770. m_childGuiHelper->syncPhysicsToGraphics2(rbWorld);
  771. }
  772. virtual void syncPhysicsToGraphics2(const GUISyncPosition* positions, int numPositions)
  773. {
  774. m_childGuiHelper->syncPhysicsToGraphics2(positions, numPositions);
  775. }
  776. virtual void render(const btDiscreteDynamicsWorld* rbWorld)
  777. {
  778. m_childGuiHelper->render(0);
  779. }
  780. virtual void createPhysicsDebugDrawer(btDiscreteDynamicsWorld* rbWorld)
  781. {
  782. btAssert(rbWorld);
  783. if (m_debugDraw)
  784. {
  785. delete m_debugDraw;
  786. m_debugDraw = 0;
  787. }
  788. m_debugDraw = new MultithreadedDebugDrawer(this);
  789. rbWorld->setDebugDrawer(m_debugDraw);
  790. //m_childGuiHelper->createPhysicsDebugDrawer(rbWorld);
  791. }
  792. int m_removeTextureUid;
  793. virtual void removeTexture(int textureUid)
  794. {
  795. m_cs->lock();
  796. m_removeTextureUid = textureUid;
  797. setSharedParam(1, eGUIHelperRemoveTexture);
  798. workerThreadWait();
  799. }
  800. int m_updateShapeIndex;
  801. float* m_updateShapeVertices;
  802. int m_updateNumShapeVertices;
  803. virtual void updateShape(int shapeIndex, float* vertices, int numVertices)
  804. {
  805. m_cs->lock();
  806. m_updateShapeIndex = shapeIndex;
  807. m_updateShapeVertices = vertices;
  808. m_updateNumShapeVertices = numVertices;
  809. setSharedParam(1, eGUIHelperUpdateShape);
  810. workerThreadWait();
  811. }
  812. virtual int registerTexture(const unsigned char* texels, int width, int height)
  813. {
  814. int* cachedTexture = m_cachedTextureIds[texels];
  815. if (cachedTexture)
  816. {
  817. return *cachedTexture;
  818. }
  819. m_cs->lock();
  820. m_texels = texels;
  821. m_textureWidth = width;
  822. m_textureHeight = height;
  823. setSharedParam(1, eGUIHelperRegisterTexture);
  824. workerThreadWait();
  825. m_cachedTextureIds.insert(texels, m_textureId);
  826. return m_textureId;
  827. }
  828. virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType, int textureId)
  829. {
  830. m_cs->lock();
  831. m_csGUI->lock();
  832. m_vertices = vertices;
  833. m_numvertices = numvertices;
  834. m_indices = indices;
  835. m_numIndices = numIndices;
  836. m_primitiveType = primitiveType;
  837. m_textureId = textureId;
  838. m_csGUI->unlock();
  839. setSharedParam(1, eGUIHelperRegisterGraphicsShape);
  840. workerThreadWait();
  841. m_csGUI->lock();
  842. int shapeIndex = m_shapeIndex;
  843. m_csGUI->unlock();
  844. return shapeIndex;
  845. }
  846. int m_visualizerFlag;
  847. int m_visualizerEnable;
  848. int m_renderedFrames;
  849. void setSharedParam(int slot, int param)
  850. {
  851. m_csGUI->lock();
  852. m_cs->setSharedParam(slot, param);
  853. m_csGUI->unlock();
  854. }
  855. void setVisualizerFlag(int flag, int enable)
  856. {
  857. m_cs->lock();
  858. m_visualizerFlag = flag;
  859. m_visualizerEnable = enable;
  860. setSharedParam(1, eGUIHelperSetVisualizerFlag);
  861. workerThreadWait();
  862. }
  863. void setVisualizerFlagCallback(VisualizerFlagCallback callback)
  864. {
  865. m_childGuiHelper->setVisualizerFlagCallback(callback);
  866. }
  867. virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling)
  868. {
  869. m_shapeIndex = shapeIndex;
  870. m_position = position;
  871. m_quaternion = quaternion;
  872. m_color = color;
  873. m_scaling = scaling;
  874. m_cs->lock();
  875. setSharedParam(1, eGUIHelperRegisterGraphicsInstance);
  876. workerThreadWait();
  877. return m_instanceId;
  878. }
  879. virtual void removeAllGraphicsInstances()
  880. {
  881. m_cs->lock();
  882. m_cachedTextureIds.clear();
  883. setSharedParam(1, eGUIHelperRemoveAllGraphicsInstances);
  884. workerThreadWait();
  885. }
  886. int m_graphicsInstanceRemove;
  887. virtual void removeGraphicsInstance(int graphicsUid)
  888. {
  889. m_graphicsInstanceRemove = graphicsUid;
  890. m_cs->lock();
  891. setSharedParam(1, eGUIHelperRemoveGraphicsInstance);
  892. workerThreadWait();
  893. }
  894. int m_getShapeIndex_instance;
  895. int getShapeIndex_shapeIndex;
  896. virtual int getShapeIndexFromInstance(int instance)
  897. {
  898. m_getShapeIndex_instance = instance;
  899. m_cs->lock();
  900. setSharedParam(1, eGUIHelperGetShapeIndexFromInstance);
  901. getShapeIndex_shapeIndex = -1;
  902. workerThreadWait();
  903. return getShapeIndex_shapeIndex;
  904. }
  905. int m_graphicsInstanceChangeTextureId;
  906. int m_graphicsInstanceChangeTextureShapeIndex;
  907. virtual void replaceTexture(int shapeIndex, int textureUid)
  908. {
  909. m_graphicsInstanceChangeTextureShapeIndex = shapeIndex;
  910. m_graphicsInstanceChangeTextureId = textureUid;
  911. m_cs->lock();
  912. setSharedParam(1, eGUIHelperChangeGraphicsInstanceTextureId);
  913. workerThreadWait();
  914. }
  915. int m_changeTextureUniqueId;
  916. const unsigned char* m_changeTextureRgbTexels;
  917. int m_changeTextureWidth;
  918. int m_changeTextureHeight;
  919. virtual void changeTexture(int textureUniqueId, const unsigned char* rgbTexels, int width, int height)
  920. {
  921. m_changeTextureUniqueId = textureUniqueId;
  922. m_changeTextureRgbTexels = rgbTexels;
  923. m_changeTextureWidth = width;
  924. m_changeTextureHeight = height;
  925. m_cs->lock();
  926. setSharedParam(1, eGUIHelperChangeTexture);
  927. workerThreadWait();
  928. }
  929. double m_rgbaColor[4];
  930. int m_graphicsInstanceChangeColor;
  931. virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4])
  932. {
  933. m_graphicsInstanceChangeColor = instanceUid;
  934. m_rgbaColor[0] = rgbaColor[0];
  935. m_rgbaColor[1] = rgbaColor[1];
  936. m_rgbaColor[2] = rgbaColor[2];
  937. m_rgbaColor[3] = rgbaColor[3];
  938. m_cs->lock();
  939. setSharedParam(1, eGUIHelperChangeGraphicsInstanceRGBAColor);
  940. workerThreadWait();
  941. }
  942. int m_graphicsInstanceFlagsInstanceUid;
  943. int m_graphicsInstanceFlags;
  944. virtual void changeInstanceFlags(int instanceUid, int flags)
  945. {
  946. m_graphicsInstanceFlagsInstanceUid = instanceUid;
  947. m_graphicsInstanceFlags = flags;
  948. m_cs->lock();
  949. setSharedParam(1, eGUIHelperChangeGraphicsInstanceFlags);
  950. workerThreadWait();
  951. }
  952. double m_rgbBackground[3];
  953. virtual void setBackgroundColor(const double rgbBackground[3])
  954. {
  955. m_cs->lock();
  956. m_rgbBackground[0] = rgbBackground[0];
  957. m_rgbBackground[1] = rgbBackground[1];
  958. m_rgbBackground[2] = rgbBackground[2];
  959. setSharedParam(1, eGUIHelperSetRgbBackground);
  960. workerThreadWait();
  961. }
  962. int m_graphicsInstanceChangeScaling;
  963. double m_baseScaling[3];
  964. virtual void changeScaling(int instanceUid, const double scaling[3])
  965. {
  966. m_graphicsInstanceChangeScaling = instanceUid;
  967. m_baseScaling[0] = scaling[0];
  968. m_baseScaling[1] = scaling[1];
  969. m_baseScaling[2] = scaling[2];
  970. m_cs->lock();
  971. setSharedParam(1, eGUIHelperChangeGraphicsInstanceScaling);
  972. workerThreadWait();
  973. }
  974. double m_specularColor[3];
  975. int m_graphicsInstanceChangeSpecular;
  976. virtual void changeSpecularColor(int instanceUid, const double specularColor[3])
  977. {
  978. m_graphicsInstanceChangeSpecular = instanceUid;
  979. m_specularColor[0] = specularColor[0];
  980. m_specularColor[1] = specularColor[1];
  981. m_specularColor[2] = specularColor[2];
  982. m_cs->lock();
  983. setSharedParam(1, eGUIHelperChangeGraphicsInstanceSpecularColor);
  984. workerThreadWait();
  985. }
  986. virtual Common2dCanvasInterface* get2dCanvasInterface()
  987. {
  988. return m_childGuiHelper->get2dCanvasInterface();
  989. }
  990. virtual CommonParameterInterface* getParameterInterface()
  991. {
  992. return 0;
  993. }
  994. virtual CommonRenderInterface* getRenderInterface()
  995. {
  996. return m_childGuiHelper->getRenderInterface();
  997. }
  998. virtual CommonGraphicsApp* getAppInterface()
  999. {
  1000. return m_childGuiHelper->getAppInterface();
  1001. }
  1002. virtual void setUpAxis(int axis)
  1003. {
  1004. m_childGuiHelper->setUpAxis(axis);
  1005. }
  1006. bool m_cameraUpdated;
  1007. float m_resetCameraCamDist;
  1008. float m_resetCameraYaw;
  1009. float m_resetCameraPitch;
  1010. float m_resetCameraCamPosX;
  1011. float m_resetCameraCamPosY;
  1012. float m_resetCameraCamPosZ;
  1013. virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX, float camPosY, float camPosZ)
  1014. {
  1015. m_csGUI->lock();
  1016. m_cameraUpdated = true;
  1017. m_resetCameraCamDist = camDist;
  1018. m_resetCameraYaw = yaw;
  1019. m_resetCameraPitch = pitch;
  1020. m_resetCameraCamPosX = camPosX;
  1021. m_resetCameraCamPosY = camPosY;
  1022. m_resetCameraCamPosZ = camPosZ;
  1023. #ifdef SYNC_CAMERA_USING_GUI_CS
  1024. m_csGUI->unlock();
  1025. #else
  1026. setSharedParam(1, eGUIHelperResetCamera);
  1027. workerThreadWait();
  1028. m_childGuiHelper->resetCamera(camDist, yaw, pitch, camPosX, camPosY, camPosZ);
  1029. #endif //SYNC_CAMERA_USING_GUI_CS
  1030. }
  1031. virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3], float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
  1032. {
  1033. return m_childGuiHelper->getCameraInfo(width, height, viewMatrix, projectionMatrix, camUp, camForward, hor, vert, yaw, pitch, camDist, camTarget);
  1034. }
  1035. float m_viewMatrix[16];
  1036. float m_projectionMatrix[16];
  1037. unsigned char* m_pixelsRGBA;
  1038. int m_rgbaBufferSizeInPixels;
  1039. float* m_depthBuffer;
  1040. int m_depthBufferSizeInPixels;
  1041. int* m_segmentationMaskBuffer;
  1042. int m_segmentationMaskBufferSizeInPixels;
  1043. int m_startPixelIndex;
  1044. int m_destinationWidth;
  1045. int m_destinationHeight;
  1046. int* m_numPixelsCopied;
  1047. virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
  1048. unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
  1049. float* depthBuffer, int depthBufferSizeInPixels,
  1050. int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels,
  1051. int startPixelIndex, int destinationWidth,
  1052. int destinationHeight, int* numPixelsCopied)
  1053. {
  1054. m_cs->lock();
  1055. for (int i = 0; i < 16; i++)
  1056. {
  1057. m_viewMatrix[i] = viewMatrix[i];
  1058. m_projectionMatrix[i] = projectionMatrix[i];
  1059. }
  1060. m_pixelsRGBA = pixelsRGBA;
  1061. m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
  1062. m_depthBuffer = depthBuffer;
  1063. m_depthBufferSizeInPixels = depthBufferSizeInPixels;
  1064. m_segmentationMaskBuffer = segmentationMaskBuffer;
  1065. m_segmentationMaskBufferSizeInPixels = segmentationMaskBufferSizeInPixels;
  1066. m_startPixelIndex = startPixelIndex;
  1067. m_destinationWidth = destinationWidth;
  1068. m_destinationHeight = destinationHeight;
  1069. m_numPixelsCopied = numPixelsCopied;
  1070. setSharedParam(1, eGUIHelperCopyCameraImageData);
  1071. workerThreadWait();
  1072. }
  1073. virtual void debugDisplayCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
  1074. unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
  1075. float* depthBuffer, int depthBufferSizeInPixels,
  1076. int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels,
  1077. int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
  1078. {
  1079. m_cs->lock();
  1080. for (int i = 0; i < 16; i++)
  1081. {
  1082. m_viewMatrix[i] = viewMatrix[i];
  1083. m_projectionMatrix[i] = projectionMatrix[i];
  1084. }
  1085. m_pixelsRGBA = pixelsRGBA;
  1086. m_rgbaBufferSizeInPixels = rgbaBufferSizeInPixels;
  1087. m_depthBuffer = depthBuffer;
  1088. m_depthBufferSizeInPixels = depthBufferSizeInPixels;
  1089. m_segmentationMaskBuffer = segmentationMaskBuffer;
  1090. m_segmentationMaskBufferSizeInPixels = segmentationMaskBufferSizeInPixels;
  1091. m_startPixelIndex = startPixelIndex;
  1092. m_destinationWidth = destinationWidth;
  1093. m_destinationHeight = destinationHeight;
  1094. m_numPixelsCopied = numPixelsCopied;
  1095. setSharedParam(1, eGUIHelperDisplayCameraImageData);
  1096. workerThreadWait();
  1097. }
  1098. virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16])
  1099. {
  1100. if (m_childGuiHelper->getAppInterface() && m_childGuiHelper->getAppInterface()->m_renderer)
  1101. {
  1102. m_childGuiHelper->getAppInterface()->m_renderer->setProjectiveTextureMatrices(viewMatrix, projectionMatrix);
  1103. }
  1104. }
  1105. virtual void setProjectiveTexture(bool useProjectiveTexture)
  1106. {
  1107. if (m_childGuiHelper->getAppInterface() && m_childGuiHelper->getAppInterface()->m_renderer)
  1108. {
  1109. m_childGuiHelper->getAppInterface()->m_renderer->setProjectiveTexture(useProjectiveTexture);
  1110. }
  1111. }
  1112. btDiscreteDynamicsWorld* m_dynamicsWorld;
  1113. virtual void autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWorld)
  1114. {
  1115. m_dynamicsWorld = rbWorld;
  1116. m_cs->lock();
  1117. setSharedParam(1, eGUIHelperAutogenerateGraphicsObjects);
  1118. workerThreadWait();
  1119. }
  1120. virtual void drawText3D(const char* txt, float posX, float posZY, float posZ, float size)
  1121. {
  1122. }
  1123. virtual void drawText3D(const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag)
  1124. {
  1125. }
  1126. btAlignedObjectArray<UserDebugText> m_userDebugText;
  1127. UserDebugText m_tmpText;
  1128. int m_resultUserDebugTextUid;
  1129. virtual int addUserDebugText3D(const char* txt, const double positionXYZ[3], const double orientation[4], const double textColorRGB[3], double size, double lifeTime, int trackingVisualShapeIndex, int optionFlags, int replaceItemUid)
  1130. {
  1131. if (replaceItemUid >= 0)
  1132. {
  1133. m_tmpText.m_itemUniqueId = replaceItemUid;
  1134. }
  1135. else
  1136. {
  1137. m_tmpText.m_itemUniqueId = m_uidGenerator++;
  1138. }
  1139. m_tmpText.m_lifeTime = lifeTime;
  1140. m_tmpText.textSize = size;
  1141. //int len = strlen(txt);
  1142. strcpy(m_tmpText.m_text, txt);
  1143. m_tmpText.m_textPositionXYZ1[0] = positionXYZ[0];
  1144. m_tmpText.m_textPositionXYZ1[1] = positionXYZ[1];
  1145. m_tmpText.m_textPositionXYZ1[2] = positionXYZ[2];
  1146. m_tmpText.m_textOrientation[0] = orientation[0];
  1147. m_tmpText.m_textOrientation[1] = orientation[1];
  1148. m_tmpText.m_textOrientation[2] = orientation[2];
  1149. m_tmpText.m_textOrientation[3] = orientation[3];
  1150. m_tmpText.m_textColorRGB[0] = textColorRGB[0];
  1151. m_tmpText.m_textColorRGB[1] = textColorRGB[1];
  1152. m_tmpText.m_textColorRGB[2] = textColorRGB[2];
  1153. m_tmpText.m_trackingVisualShapeIndex = trackingVisualShapeIndex;
  1154. m_tmpText.m_optionFlags = optionFlags;
  1155. m_tmpText.m_textOrientation[0] = orientation[0];
  1156. m_tmpText.m_textOrientation[1] = orientation[1];
  1157. m_tmpText.m_textOrientation[2] = orientation[2];
  1158. m_tmpText.m_textOrientation[3] = orientation[3];
  1159. m_cs->lock();
  1160. setSharedParam(1, eGUIUserDebugAddText);
  1161. m_resultUserDebugTextUid = -1;
  1162. workerThreadWait();
  1163. return m_resultUserDebugTextUid;
  1164. }
  1165. btAlignedObjectArray<UserDebugParameter*> m_userDebugParams;
  1166. UserDebugParameter m_tmpParam;
  1167. virtual int readUserDebugParameter(int itemUniqueId, double* value)
  1168. {
  1169. for (int i = 0; i < m_userDebugParams.size(); i++)
  1170. {
  1171. if (m_userDebugParams[i]->m_itemUniqueId == itemUniqueId)
  1172. {
  1173. *value = m_userDebugParams[i]->m_value;
  1174. return 1;
  1175. }
  1176. }
  1177. return 0;
  1178. }
  1179. int m_userDebugParamUid;
  1180. virtual int addUserDebugParameter(const char* txt, double rangeMin, double rangeMax, double startValue)
  1181. {
  1182. strcpy(m_tmpParam.m_text, txt);
  1183. m_tmpParam.m_rangeMin = rangeMin;
  1184. m_tmpParam.m_rangeMax = rangeMax;
  1185. m_tmpParam.m_value = startValue;
  1186. m_tmpParam.m_itemUniqueId = m_uidGenerator++;
  1187. m_cs->lock();
  1188. setSharedParam(1, eGUIUserDebugAddParameter);
  1189. m_userDebugParamUid = -1;
  1190. workerThreadWait();
  1191. return m_userDebugParamUid;
  1192. }
  1193. btAlignedObjectArray<UserDebugDrawLine> m_userDebugLines;
  1194. UserDebugDrawLine m_tmpLine;
  1195. int m_resultDebugLineUid;
  1196. virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid)
  1197. {
  1198. m_tmpLine.m_lifeTime = lifeTime;
  1199. m_tmpLine.m_lineWidth = lineWidth;
  1200. m_tmpLine.m_itemUniqueId = replaceItemUid < 0 ? m_uidGenerator++ : replaceItemUid;
  1201. m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0];
  1202. m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1];
  1203. m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2];
  1204. m_tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0];
  1205. m_tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1];
  1206. m_tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2];
  1207. m_tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0];
  1208. m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1];
  1209. m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2];
  1210. m_tmpLine.m_trackingVisualShapeIndex = trackingVisualShapeIndex;
  1211. m_tmpLine.m_replaceItemUid = replaceItemUid;
  1212. //don't block when replacing an item
  1213. if (replaceItemUid>=0 && replaceItemUid<m_userDebugLines.size())
  1214. {
  1215. //find the right slot
  1216. int slot=-1;
  1217. for (int i=0;i<m_userDebugLines.size();i++)
  1218. {
  1219. if (replaceItemUid == m_userDebugLines[i].m_itemUniqueId)
  1220. {
  1221. slot = i;
  1222. }
  1223. }
  1224. if (slot>=0)
  1225. {
  1226. m_userDebugLines[slot] = m_tmpLine;
  1227. }
  1228. m_resultDebugLineUid = replaceItemUid;
  1229. }
  1230. else
  1231. {
  1232. m_cs->lock();
  1233. setSharedParam(1, eGUIUserDebugAddLine);
  1234. m_resultDebugLineUid = -1;
  1235. workerThreadWait();
  1236. }
  1237. return m_resultDebugLineUid;
  1238. }
  1239. btAlignedObjectArray<UserDebugDrawPoint> m_userDebugPoints;
  1240. UserDebugDrawPoint m_tmpPoint;
  1241. int m_resultDebugPointUid;
  1242. virtual int addUserDebugPoints(const double* debugPointPositions, const double* debugPointColors, double pointSize, double lifeTime, int trackingVisualShapeIndex, int replaceItemUid, int debugPointNum)
  1243. {
  1244. m_tmpPoint.m_lifeTime = lifeTime;
  1245. m_tmpPoint.m_pointSize = pointSize;
  1246. m_tmpPoint.m_itemUniqueId = replaceItemUid < 0 ? m_uidGenerator++ : replaceItemUid;
  1247. m_tmpPoint.m_debugPointPositions = debugPointPositions;
  1248. m_tmpPoint.m_debugPointColors = debugPointColors;
  1249. m_tmpPoint.m_debugPointNum = debugPointNum;
  1250. m_tmpPoint.m_trackingVisualShapeIndex = trackingVisualShapeIndex;
  1251. m_tmpPoint.m_replaceItemUid = replaceItemUid;
  1252. //don't block when replacing an item
  1253. if (replaceItemUid>=0 && replaceItemUid<m_userDebugPoints.size())
  1254. {
  1255. //find the right slot
  1256. int slot=-1;
  1257. for (int i=0;i<m_userDebugPoints.size();i++)
  1258. {
  1259. if (replaceItemUid == m_userDebugPoints[i].m_itemUniqueId)
  1260. {
  1261. slot = i;
  1262. }
  1263. }
  1264. if (slot>=0)
  1265. {
  1266. m_userDebugPoints[slot] = m_tmpPoint;
  1267. }
  1268. m_resultDebugPointUid = replaceItemUid;
  1269. }
  1270. else
  1271. {
  1272. m_cs->lock();
  1273. setSharedParam(1, eGUIUserDebugAddPoints);
  1274. m_resultDebugPointUid = -1;
  1275. workerThreadWait();
  1276. }
  1277. return m_resultDebugPointUid;
  1278. }
  1279. int m_removeDebugItemUid;
  1280. virtual void removeUserDebugItem(int debugItemUniqueId)
  1281. {
  1282. m_removeDebugItemUid = debugItemUniqueId;
  1283. m_cs->lock();
  1284. setSharedParam(1, eGUIUserDebugRemoveItem);
  1285. workerThreadWait();
  1286. }
  1287. virtual void removeAllUserDebugItems()
  1288. {
  1289. m_cs->lock();
  1290. setSharedParam(1, eGUIUserDebugRemoveAllItems);
  1291. workerThreadWait();
  1292. }
  1293. virtual void removeAllUserParameters()
  1294. {
  1295. m_cs->lock();
  1296. setSharedParam(1, eGUIUserDebugRemoveAllParameters);
  1297. workerThreadWait();
  1298. }
  1299. const char* m_mp4FileName;
  1300. virtual void dumpFramesToVideo(const char* mp4FileName)
  1301. {
  1302. m_cs->lock();
  1303. m_mp4FileName = mp4FileName;
  1304. setSharedParam(1, eGUIDumpFramesToVideo);
  1305. workerThreadWait();
  1306. m_mp4FileName = 0;
  1307. }
  1308. };
  1309. class PhysicsServerExample : public SharedMemoryCommon
  1310. {
  1311. PhysicsServerSharedMemory m_physicsServer;
  1312. b3ThreadSupportInterface* m_threadSupport;
  1313. MotionArgs m_args[MAX_MOTION_NUM_THREADS];
  1314. MultiThreadedOpenGLGuiHelper* m_multiThreadedHelper;
  1315. bool m_wantsShutdown;
  1316. bool m_isConnected;
  1317. btClock m_clock;
  1318. bool m_replay;
  1319. struct Common2dCanvasInterface* m_canvas;
  1320. int m_canvasRGBIndex;
  1321. int m_canvasDepthIndex;
  1322. int m_canvasSegMaskIndex;
  1323. // int m_options;
  1324. #ifdef BT_ENABLE_VR
  1325. TinyVRGui* m_tinyVrGui;
  1326. #endif
  1327. int m_renderedFrames;
  1328. public:
  1329. PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem = 0, int options = 0);
  1330. virtual ~PhysicsServerExample();
  1331. virtual void initPhysics();
  1332. virtual void stepSimulation(float deltaTime);
  1333. virtual void updateGraphics();
  1334. void enableCommandLogging()
  1335. {
  1336. m_physicsServer.enableCommandLogging(true, "BulletPhysicsCommandLog.bin");
  1337. }
  1338. void replayFromLogFile()
  1339. {
  1340. m_replay = true;
  1341. m_physicsServer.replayFromLogFile("BulletPhysicsCommandLog.bin");
  1342. }
  1343. virtual void resetCamera()
  1344. {
  1345. float dist = 5;
  1346. float pitch = -35;
  1347. float yaw = 50;
  1348. float targetPos[3] = {0, 0, 0}; //-3,2.8,-2.5};
  1349. m_multiThreadedHelper->m_childGuiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
  1350. }
  1351. virtual bool wantsTermination();
  1352. virtual bool isConnected();
  1353. virtual void renderScene();
  1354. void drawUserDebugLines();
  1355. virtual void exitPhysics();
  1356. virtual void physicsDebugDraw(int debugFlags);
  1357. btVector3 getRayTo(int x, int y);
  1358. virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4]);
  1359. virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis, float auxAnalogAxes[10]);
  1360. virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]);
  1361. virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]);
  1362. virtual bool mouseMoveCallback(float x, float y)
  1363. {
  1364. if (m_replay)
  1365. return false;
  1366. CommonRenderInterface* renderer = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface(); // m_guiHelper->getRenderInterface();
  1367. if (!renderer)
  1368. {
  1369. return false;
  1370. }
  1371. b3MouseEvent event;
  1372. event.m_buttonState = 0;
  1373. event.m_buttonIndex = -1;
  1374. event.m_mousePosX = x;
  1375. event.m_mousePosY = y;
  1376. event.m_eventType = MOUSE_MOVE_EVENT;
  1377. m_args[0].m_csGUI->lock();
  1378. m_args[0].m_allMouseEvents.push_back(event);
  1379. m_args[0].m_csGUI->unlock();
  1380. btVector3 rayTo = getRayTo(int(x), int(y));
  1381. btVector3 rayFrom;
  1382. renderer->getActiveCamera()->getCameraPosition(rayFrom);
  1383. MyMouseCommand cmd;
  1384. cmd.m_rayFrom = rayFrom;
  1385. cmd.m_rayTo = rayTo;
  1386. cmd.m_type = MyMouseMove;
  1387. m_args[0].m_csGUI->lock();
  1388. m_args[0].m_mouseCommands.push_back(cmd);
  1389. m_args[0].m_csGUI->unlock();
  1390. return false;
  1391. };
  1392. virtual bool mouseButtonCallback(int button, int state, float x, float y)
  1393. {
  1394. if (m_replay)
  1395. return false;
  1396. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  1397. if (!renderer)
  1398. {
  1399. return false;
  1400. }
  1401. CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
  1402. b3MouseEvent event;
  1403. event.m_buttonIndex = button;
  1404. event.m_mousePosX = x;
  1405. event.m_mousePosY = y;
  1406. event.m_eventType = MOUSE_BUTTON_EVENT;
  1407. if (state)
  1408. {
  1409. event.m_buttonState = eButtonIsDown + eButtonTriggered;
  1410. }
  1411. else
  1412. {
  1413. event.m_buttonState = eButtonReleased;
  1414. }
  1415. m_args[0].m_csGUI->lock();
  1416. m_args[0].m_allMouseEvents.push_back(event);
  1417. m_args[0].m_csGUI->unlock();
  1418. if (state == 1)
  1419. {
  1420. if (button == 0 && (!window->isModifierKeyPressed(B3G_ALT) && !window->isModifierKeyPressed(B3G_CONTROL)))
  1421. {
  1422. btVector3 camPos;
  1423. renderer->getActiveCamera()->getCameraPosition(camPos);
  1424. btVector3 rayFrom = camPos;
  1425. btVector3 rayTo = getRayTo(int(x), int(y));
  1426. MyMouseCommand cmd;
  1427. cmd.m_rayFrom = rayFrom;
  1428. cmd.m_rayTo = rayTo;
  1429. cmd.m_type = MyMouseButtonDown;
  1430. m_args[0].m_csGUI->lock();
  1431. m_args[0].m_mouseCommands.push_back(cmd);
  1432. m_args[0].m_csGUI->unlock();
  1433. }
  1434. }
  1435. else
  1436. {
  1437. if (button == 0)
  1438. {
  1439. //m_physicsServer.removePickingConstraint();
  1440. MyMouseCommand cmd;
  1441. cmd.m_rayFrom.setValue(0, 0, 0);
  1442. cmd.m_rayTo.setValue(0, 0, 0);
  1443. cmd.m_type = MyMouseButtonUp;
  1444. m_args[0].m_csGUI->lock();
  1445. m_args[0].m_mouseCommands.push_back(cmd);
  1446. m_args[0].m_csGUI->unlock();
  1447. //remove p2p
  1448. }
  1449. }
  1450. //printf("button=%d, state=%d\n",button,state);
  1451. return false;
  1452. }
  1453. virtual bool keyboardCallback(int key, int state)
  1454. {
  1455. //printf("key=%d, state=%d\n", key,state);
  1456. {
  1457. m_args[0].m_csGUI->lock();
  1458. int keyIndex = -1;
  1459. //is already there?
  1460. for (int i = 0; i < m_args[0].m_keyboardEvents.size(); i++)
  1461. {
  1462. if (m_args[0].m_keyboardEvents[i].m_keyCode == key)
  1463. {
  1464. keyIndex = i;
  1465. break;
  1466. }
  1467. }
  1468. if (state)
  1469. {
  1470. b3KeyboardEvent ev;
  1471. ev.m_keyCode = key;
  1472. ev.m_keyState = eButtonIsDown + eButtonTriggered;
  1473. if (keyIndex >= 0)
  1474. {
  1475. if (0 == (m_args[0].m_keyboardEvents[keyIndex].m_keyState & eButtonIsDown))
  1476. {
  1477. m_args[0].m_keyboardEvents[keyIndex] = ev;
  1478. }
  1479. }
  1480. else
  1481. {
  1482. m_args[0].m_keyboardEvents.push_back(ev);
  1483. }
  1484. }
  1485. else
  1486. {
  1487. b3KeyboardEvent ev;
  1488. ev.m_keyCode = key;
  1489. ev.m_keyState = eButtonReleased;
  1490. if (keyIndex >= 0)
  1491. {
  1492. m_args[0].m_keyboardEvents[keyIndex] = ev;
  1493. }
  1494. else
  1495. {
  1496. m_args[0].m_keyboardEvents.push_back(ev);
  1497. }
  1498. }
  1499. m_args[0].m_csGUI->unlock();
  1500. }
  1501. /*printf("m_args[0].m_keyboardEvents.size()=%d\n", m_args[0].m_keyboardEvents.size());
  1502. for (int i=0;i<m_args[0].m_keyboardEvents.size();i++)
  1503. {
  1504. printf("key[%d]=%d state = %d\n",i,m_args[0].m_keyboardEvents[i].m_keyCode,m_args[0].m_keyboardEvents[i].m_keyState);
  1505. }
  1506. */
  1507. double shift = 0.1;
  1508. CommonWindowInterface* window = m_guiHelper->getAppInterface()->m_window;
  1509. if (window->isModifierKeyPressed(B3G_SHIFT))
  1510. shift = 0.01;
  1511. btVector3 VRTeleportPos = this->m_physicsServer.getVRTeleportPosition();
  1512. if (gEnableDefaultKeyboardShortcuts)
  1513. {
  1514. if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
  1515. {
  1516. if (key == 'w' && state)
  1517. {
  1518. VRTeleportPos[0] += shift;
  1519. m_physicsServer.setVRTeleportPosition(VRTeleportPos);
  1520. saveCurrentSettingsVR(VRTeleportPos);
  1521. }
  1522. if (key == 's' && state)
  1523. {
  1524. VRTeleportPos[0] -= shift;
  1525. m_physicsServer.setVRTeleportPosition(VRTeleportPos);
  1526. saveCurrentSettingsVR(VRTeleportPos);
  1527. }
  1528. if (key == 'a' && state)
  1529. {
  1530. VRTeleportPos[1] -= shift;
  1531. m_physicsServer.setVRTeleportPosition(VRTeleportPos);
  1532. saveCurrentSettingsVR(VRTeleportPos);
  1533. }
  1534. if (key == 'd' && state)
  1535. {
  1536. VRTeleportPos[1] += shift;
  1537. m_physicsServer.setVRTeleportPosition(VRTeleportPos);
  1538. saveCurrentSettingsVR(VRTeleportPos);
  1539. }
  1540. if (key == 'q' && state)
  1541. {
  1542. VRTeleportPos[2] += shift;
  1543. m_physicsServer.setVRTeleportPosition(VRTeleportPos);
  1544. saveCurrentSettingsVR(VRTeleportPos);
  1545. }
  1546. if (key == 'e' && state)
  1547. {
  1548. VRTeleportPos[2] -= shift;
  1549. m_physicsServer.setVRTeleportPosition(VRTeleportPos);
  1550. saveCurrentSettingsVR(VRTeleportPos);
  1551. }
  1552. if (key == 'z' && state)
  1553. {
  1554. gVRTeleportRotZ += shift;
  1555. btQuaternion VRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ);
  1556. m_physicsServer.setVRTeleportOrientation(VRTeleportOrn);
  1557. saveCurrentSettingsVR(VRTeleportPos);
  1558. }
  1559. }
  1560. }
  1561. return false;
  1562. }
  1563. virtual void setSharedMemoryKey(int key)
  1564. {
  1565. m_physicsServer.setSharedMemoryKey(key);
  1566. }
  1567. virtual void processCommandLineArgs(int argc, char* argv[])
  1568. {
  1569. b3CommandLineArgs args(argc, argv);
  1570. loadCurrentSettingsVR(args);
  1571. int shmemKey;
  1572. if (args.GetCmdLineArgument("sharedMemoryKey", shmemKey))
  1573. {
  1574. setSharedMemoryKey(shmemKey);
  1575. }
  1576. btVector3 vrTeleportPos = m_physicsServer.getVRTeleportPosition();
  1577. if (args.GetCmdLineArgument("camPosX", vrTeleportPos[0]))
  1578. {
  1579. printf("camPosX=%f\n", vrTeleportPos[0]);
  1580. }
  1581. if (args.GetCmdLineArgument("camPosY", vrTeleportPos[1]))
  1582. {
  1583. printf("camPosY=%f\n", vrTeleportPos[1]);
  1584. }
  1585. if (args.GetCmdLineArgument("camPosZ", vrTeleportPos[2]))
  1586. {
  1587. printf("camPosZ=%f\n", vrTeleportPos[2]);
  1588. }
  1589. m_physicsServer.setVRTeleportPosition(vrTeleportPos);
  1590. float camRotZ = 0.f;
  1591. if (args.GetCmdLineArgument("camRotZ", camRotZ))
  1592. {
  1593. printf("camRotZ = %f\n", camRotZ);
  1594. btQuaternion ornZ(btVector3(0, 0, 1), camRotZ);
  1595. m_physicsServer.setVRTeleportOrientation(ornZ);
  1596. }
  1597. if (args.CheckCmdLineFlag("realtimesimulation"))
  1598. {
  1599. //gEnableRealTimeSimVR = true;
  1600. m_physicsServer.enableRealTimeSimulation(true);
  1601. }
  1602. if (args.CheckCmdLineFlag("disableDefaultKeyboardShortcuts"))
  1603. {
  1604. gEnableDefaultKeyboardShortcuts = false;
  1605. }
  1606. if (args.CheckCmdLineFlag("enableDefaultKeyboardShortcuts"))
  1607. {
  1608. gEnableDefaultKeyboardShortcuts = true;
  1609. }
  1610. if (args.CheckCmdLineFlag("disableDefaultMousePicking"))
  1611. {
  1612. gEnableDefaultMousePicking = false;
  1613. }
  1614. if (args.CheckCmdLineFlag("enableDefaultMousePicking"))
  1615. {
  1616. gEnableDefaultMousePicking = true;
  1617. }
  1618. }
  1619. };
  1620. PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem, int options)
  1621. : SharedMemoryCommon(helper),
  1622. m_physicsServer(commandProcessorCreator, sharedMem, 0),
  1623. m_wantsShutdown(false),
  1624. m_isConnected(false),
  1625. m_replay(false),
  1626. m_canvas(0),
  1627. m_canvasRGBIndex(-1),
  1628. m_canvasDepthIndex(-1),
  1629. m_canvasSegMaskIndex(-1)
  1630. //m_options(options)
  1631. #ifdef BT_ENABLE_VR
  1632. ,
  1633. m_tinyVrGui(0)
  1634. #endif
  1635. ,
  1636. m_renderedFrames(0)
  1637. {
  1638. m_multiThreadedHelper = helper;
  1639. // b3Printf("Started PhysicsServer\n");
  1640. }
  1641. PhysicsServerExample::~PhysicsServerExample()
  1642. {
  1643. if (m_canvas)
  1644. {
  1645. if (m_canvasRGBIndex >= 0)
  1646. m_canvas->destroyCanvas(m_canvasRGBIndex);
  1647. if (m_canvasDepthIndex >= 0)
  1648. m_canvas->destroyCanvas(m_canvasDepthIndex);
  1649. if (m_canvasSegMaskIndex >= 0)
  1650. m_canvas->destroyCanvas(m_canvasSegMaskIndex);
  1651. }
  1652. #ifdef BT_ENABLE_VR
  1653. delete m_tinyVrGui;
  1654. #endif
  1655. bool deInitializeSharedMemory = true;
  1656. m_physicsServer.disconnectSharedMemory(deInitializeSharedMemory);
  1657. m_isConnected = false;
  1658. delete m_multiThreadedHelper;
  1659. }
  1660. bool PhysicsServerExample::isConnected()
  1661. {
  1662. return m_isConnected;
  1663. }
  1664. void PhysicsServerExample::initPhysics()
  1665. {
  1666. ///for this testing we use Z-axis up
  1667. int upAxis = 2;
  1668. m_guiHelper->setUpAxis(upAxis);
  1669. m_threadSupport = createMotionThreadSupport(MAX_MOTION_NUM_THREADS);
  1670. m_isConnected = m_physicsServer.connectSharedMemory(m_guiHelper);
  1671. for (int i = 0; i < m_threadSupport->getNumTasks(); i++)
  1672. {
  1673. MotionThreadLocalStorage* storage = (MotionThreadLocalStorage*)m_threadSupport->getThreadLocalMemory(i);
  1674. b3Assert(storage);
  1675. storage->threadId = i;
  1676. //storage->m_sharedMem = data->m_sharedMem;
  1677. }
  1678. for (int w = 0; w < MAX_MOTION_NUM_THREADS; w++)
  1679. {
  1680. m_args[w].m_cs = m_threadSupport->createCriticalSection();
  1681. m_args[w].m_cs2 = m_threadSupport->createCriticalSection();
  1682. m_args[w].m_cs3 = m_threadSupport->createCriticalSection();
  1683. m_args[w].m_csGUI = m_threadSupport->createCriticalSection();
  1684. m_multiThreadedHelper->setCriticalSection(m_args[w].m_cs);
  1685. m_multiThreadedHelper->setCriticalSection2(m_args[w].m_cs2);
  1686. m_multiThreadedHelper->setCriticalSection3(m_args[w].m_cs3);
  1687. m_multiThreadedHelper->setCriticalSectionGUI(m_args[w].m_csGUI);
  1688. m_args[w].m_cs->lock();
  1689. m_args[w].m_cs->setSharedParam(0, eMotionIsUnInitialized);
  1690. m_args[w].m_cs->unlock();
  1691. int numMoving = 0;
  1692. m_args[w].m_positions.resize(numMoving);
  1693. m_args[w].m_physicsServerPtr = &m_physicsServer;
  1694. //int index = 0;
  1695. m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*)&this->m_args[w], w);
  1696. bool isUninitialized = true;
  1697. while (isUninitialized)
  1698. {
  1699. m_args[w].m_cs->lock();
  1700. isUninitialized = (m_args[w].m_cs->getSharedParam(0) == eMotionIsUnInitialized);
  1701. m_args[w].m_cs->unlock();
  1702. #ifdef _WIN32
  1703. b3Clock::usleep(1000);
  1704. #endif
  1705. }
  1706. }
  1707. m_args[0].m_cs->lock();
  1708. m_args[0].m_csGUI->lock();
  1709. m_args[0].m_cs->setSharedParam(1, eGUIHelperIdle);
  1710. m_args[0].m_csGUI->unlock();
  1711. m_args[0].m_cs->unlock();
  1712. m_args[0].m_cs2->lock();
  1713. {
  1714. m_canvas = m_guiHelper->get2dCanvasInterface();
  1715. if (m_canvas)
  1716. {
  1717. m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data", gCamVisualizerWidth, gCamVisualizerHeight, 8, 55);
  1718. m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data", gCamVisualizerWidth, gCamVisualizerHeight, 8, 75 + gCamVisualizerHeight);
  1719. m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask", gCamVisualizerWidth, gCamVisualizerHeight, 8, 95 + gCamVisualizerHeight * 2);
  1720. for (int i = 0; i < gCamVisualizerWidth; i++)
  1721. {
  1722. for (int j = 0; j < gCamVisualizerHeight; j++)
  1723. {
  1724. unsigned char red = 255;
  1725. unsigned char green = 255;
  1726. unsigned char blue = 255;
  1727. unsigned char alpha = 255;
  1728. if (i == j)
  1729. {
  1730. red = 0;
  1731. green = 0;
  1732. blue = 0;
  1733. }
  1734. m_canvas->setPixel(m_canvasRGBIndex, i, j, red, green, blue, alpha);
  1735. if (m_canvasSegMaskIndex >= 0)
  1736. m_canvas->setPixel(m_canvasDepthIndex, i, j, red, green, blue, alpha);
  1737. if (m_canvasSegMaskIndex >= 0)
  1738. m_canvas->setPixel(m_canvasSegMaskIndex, i, j, red, green, blue, alpha);
  1739. }
  1740. }
  1741. m_canvas->refreshImageData(m_canvasRGBIndex);
  1742. if (m_canvasDepthIndex >= 0)
  1743. m_canvas->refreshImageData(m_canvasDepthIndex);
  1744. if (m_canvasSegMaskIndex >= 0)
  1745. m_canvas->refreshImageData(m_canvasSegMaskIndex);
  1746. }
  1747. }
  1748. }
  1749. void PhysicsServerExample::exitPhysics()
  1750. {
  1751. for (int i = 0; i < MAX_MOTION_NUM_THREADS; i++)
  1752. {
  1753. m_args[i].m_cs2->unlock();
  1754. m_args[i].m_cs->lock();
  1755. m_args[i].m_cs->setSharedParam(0, eRequestTerminateMotion);
  1756. m_args[i].m_cs->unlock();
  1757. }
  1758. int numActiveThreads = MAX_MOTION_NUM_THREADS;
  1759. while (numActiveThreads)
  1760. {
  1761. int arg0, arg1;
  1762. if (m_threadSupport->isTaskCompleted(&arg0, &arg1, 0))
  1763. {
  1764. numActiveThreads--;
  1765. printf("numActiveThreads = %d\n", numActiveThreads);
  1766. }
  1767. else
  1768. {
  1769. b3Clock::usleep(0);
  1770. }
  1771. //we need to call 'stepSimulation' to make sure that
  1772. //other threads get out of blocking state (workerThreadWait)
  1773. stepSimulation(0);
  1774. };
  1775. printf("stopping threads\n");
  1776. m_threadSupport->deleteCriticalSection(m_args[0].m_cs);
  1777. m_threadSupport->deleteCriticalSection(m_args[0].m_cs2);
  1778. m_threadSupport->deleteCriticalSection(m_args[0].m_cs3);
  1779. m_threadSupport->deleteCriticalSection(m_args[0].m_csGUI);
  1780. delete m_threadSupport;
  1781. m_threadSupport = 0;
  1782. //m_physicsServer.resetDynamicsWorld();
  1783. }
  1784. bool PhysicsServerExample::wantsTermination()
  1785. {
  1786. return m_wantsShutdown;
  1787. }
  1788. void PhysicsServerExample::updateGraphics()
  1789. {
  1790. //check if any graphics related tasks are requested
  1791. #ifdef SYNC_CAMERA_USING_GUI_CS
  1792. m_multiThreadedHelper->getCriticalSectionGUI()->lock();
  1793. if (m_multiThreadedHelper->m_cameraUpdated)
  1794. {
  1795. m_multiThreadedHelper->m_cameraUpdated = false;
  1796. m_multiThreadedHelper->m_childGuiHelper->resetCamera(
  1797. m_multiThreadedHelper->m_resetCameraCamDist,
  1798. m_multiThreadedHelper->m_resetCameraYaw,
  1799. m_multiThreadedHelper->m_resetCameraPitch,
  1800. m_multiThreadedHelper->m_resetCameraCamPosX,
  1801. m_multiThreadedHelper->m_resetCameraCamPosY,
  1802. m_multiThreadedHelper->m_resetCameraCamPosZ);
  1803. }
  1804. m_multiThreadedHelper->getCriticalSectionGUI()->unlock();
  1805. #endif
  1806. m_multiThreadedHelper->getCriticalSectionGUI()->lock();
  1807. unsigned int cachedSharedParam = m_multiThreadedHelper->getCriticalSection()->getSharedParam(1);
  1808. m_multiThreadedHelper->getCriticalSectionGUI()->unlock();
  1809. switch (cachedSharedParam)
  1810. {
  1811. case eGUIHelperCreateCollisionShapeGraphicsObject:
  1812. {
  1813. B3_PROFILE("eGUIHelperCreateCollisionShapeGraphicsObject");
  1814. m_multiThreadedHelper->m_childGuiHelper->createCollisionShapeGraphicsObject(m_multiThreadedHelper->m_colShape);
  1815. m_multiThreadedHelper->mainThreadRelease();
  1816. break;
  1817. }
  1818. case eGUIHelperCreateCollisionObjectGraphicsObject:
  1819. {
  1820. B3_PROFILE("eGUIHelperCreateCollisionObjectGraphicsObject");
  1821. m_multiThreadedHelper->m_childGuiHelper->createCollisionObjectGraphicsObject(m_multiThreadedHelper->m_obj,
  1822. m_multiThreadedHelper->m_color2);
  1823. m_multiThreadedHelper->mainThreadRelease();
  1824. break;
  1825. }
  1826. case eGUIHelperCreateRigidBodyGraphicsObject:
  1827. {
  1828. B3_PROFILE("eGUIHelperCreateRigidBodyGraphicsObject");
  1829. m_multiThreadedHelper->m_childGuiHelper->createRigidBodyGraphicsObject(m_multiThreadedHelper->m_body, m_multiThreadedHelper->m_color3);
  1830. m_multiThreadedHelper->mainThreadRelease();
  1831. break;
  1832. }
  1833. case eGUIHelperRegisterTexture:
  1834. {
  1835. B3_PROFILE("eGUIHelperRegisterTexture");
  1836. m_multiThreadedHelper->m_textureId = m_multiThreadedHelper->m_childGuiHelper->registerTexture(m_multiThreadedHelper->m_texels,
  1837. m_multiThreadedHelper->m_textureWidth, m_multiThreadedHelper->m_textureHeight);
  1838. m_multiThreadedHelper->mainThreadRelease();
  1839. break;
  1840. }
  1841. case eGUIHelperRemoveTexture:
  1842. {
  1843. B3_PROFILE("eGUIHelperRemoveTexture");
  1844. m_multiThreadedHelper->m_childGuiHelper->removeTexture(m_multiThreadedHelper->m_removeTextureUid);
  1845. m_multiThreadedHelper->mainThreadRelease();
  1846. break;
  1847. }
  1848. case eGUIHelperUpdateShape:
  1849. {
  1850. B3_PROFILE("eGUIHelperUpdateShape");
  1851. m_multiThreadedHelper->m_childGuiHelper->updateShape(m_multiThreadedHelper->m_updateShapeIndex, m_multiThreadedHelper->m_updateShapeVertices, m_multiThreadedHelper->m_updateNumShapeVertices);
  1852. m_multiThreadedHelper->mainThreadRelease();
  1853. break;
  1854. }
  1855. case eGUIHelperRegisterGraphicsShape:
  1856. {
  1857. B3_PROFILE("eGUIHelperRegisterGraphicsShape");
  1858. int shapeIndex = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsShape(
  1859. m_multiThreadedHelper->m_vertices,
  1860. m_multiThreadedHelper->m_numvertices,
  1861. m_multiThreadedHelper->m_indices,
  1862. m_multiThreadedHelper->m_numIndices,
  1863. m_multiThreadedHelper->m_primitiveType,
  1864. m_multiThreadedHelper->m_textureId);
  1865. m_multiThreadedHelper->getCriticalSectionGUI()->lock();
  1866. m_multiThreadedHelper->m_shapeIndex = shapeIndex;
  1867. m_multiThreadedHelper->getCriticalSectionGUI()->unlock();
  1868. m_multiThreadedHelper->mainThreadRelease();
  1869. break;
  1870. }
  1871. case eGUIHelperSetVisualizerFlag:
  1872. {
  1873. B3_PROFILE("eGUIHelperSetVisualizerFlag");
  1874. int flag = m_multiThreadedHelper->m_visualizerFlag;
  1875. int enable = m_multiThreadedHelper->m_visualizerEnable;
  1876. if (flag == COV_ENABLE_RGB_BUFFER_PREVIEW)
  1877. {
  1878. if (enable)
  1879. {
  1880. if (m_canvasRGBIndex < 0)
  1881. {
  1882. m_canvasRGBIndex = m_canvas->createCanvas("Synthetic Camera RGB data", gCamVisualizerWidth, gCamVisualizerHeight, 8, 55);
  1883. }
  1884. }
  1885. else
  1886. {
  1887. if (m_canvasRGBIndex >= 0)
  1888. {
  1889. m_canvas->destroyCanvas(m_canvasRGBIndex);
  1890. m_canvasRGBIndex = -1;
  1891. }
  1892. }
  1893. }
  1894. if (flag == COV_ENABLE_DEPTH_BUFFER_PREVIEW)
  1895. {
  1896. if (enable)
  1897. {
  1898. if (m_canvasDepthIndex < 0)
  1899. {
  1900. m_canvasDepthIndex = m_canvas->createCanvas("Synthetic Camera Depth data", gCamVisualizerWidth, gCamVisualizerHeight, 8, 75 + gCamVisualizerHeight);
  1901. }
  1902. }
  1903. else
  1904. {
  1905. if (m_canvasDepthIndex >= 0)
  1906. {
  1907. m_canvas->destroyCanvas(m_canvasDepthIndex);
  1908. m_canvasDepthIndex = -1;
  1909. }
  1910. }
  1911. }
  1912. if (flag == COV_ENABLE_SEGMENTATION_MARK_PREVIEW)
  1913. {
  1914. if (enable)
  1915. {
  1916. if (m_canvasSegMaskIndex < 0)
  1917. {
  1918. m_canvasSegMaskIndex = m_canvas->createCanvas("Synthetic Camera Segmentation Mask", gCamVisualizerWidth, gCamVisualizerHeight, 8, 95 + gCamVisualizerHeight * 2);
  1919. }
  1920. }
  1921. else
  1922. {
  1923. if (m_canvasSegMaskIndex >= 0)
  1924. {
  1925. m_canvas->destroyCanvas(m_canvasSegMaskIndex);
  1926. m_canvasSegMaskIndex = -1;
  1927. }
  1928. }
  1929. }
  1930. if (flag == COV_ENABLE_VR_TELEPORTING)
  1931. {
  1932. gEnableTeleporting = (enable != 0);
  1933. }
  1934. if (flag == COV_ENABLE_VR_PICKING)
  1935. {
  1936. gEnablePicking = (enable != 0);
  1937. }
  1938. if (flag == COV_ENABLE_SYNC_RENDERING_INTERNAL)
  1939. {
  1940. gEnableSyncPhysicsRendering = (enable != 0);
  1941. }
  1942. if (flag == COV_ENABLE_RENDERING)
  1943. {
  1944. gEnableRendering = (enable != 0);
  1945. }
  1946. if (flag == COV_ENABLE_KEYBOARD_SHORTCUTS)
  1947. {
  1948. gEnableDefaultKeyboardShortcuts = (enable != 0);
  1949. }
  1950. if (flag == COV_ENABLE_MOUSE_PICKING)
  1951. {
  1952. gEnableDefaultMousePicking = (enable != 0);
  1953. }
  1954. m_multiThreadedHelper->m_renderedFrames = m_renderedFrames;
  1955. m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag, m_multiThreadedHelper->m_visualizerEnable);
  1956. //postpone the release until an actual frame is rendered, unless it is a remote visualizer
  1957. if ((!m_multiThreadedHelper->m_childGuiHelper->isRemoteVisualizer()) && flag == COV_ENABLE_SINGLE_STEP_RENDERING)
  1958. {
  1959. m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperSetVisualizerFlagCheckRenderedFrame);
  1960. }
  1961. else
  1962. {
  1963. m_multiThreadedHelper->mainThreadRelease();
  1964. }
  1965. break;
  1966. }
  1967. case eGUIHelperSetVisualizerFlagCheckRenderedFrame:
  1968. {
  1969. if (m_renderedFrames != m_multiThreadedHelper->m_renderedFrames)
  1970. {
  1971. m_multiThreadedHelper->mainThreadRelease();
  1972. }
  1973. break;
  1974. }
  1975. case eGUIHelperRegisterGraphicsInstance:
  1976. {
  1977. B3_PROFILE("eGUIHelperRegisterGraphicsInstance");
  1978. m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance(
  1979. m_multiThreadedHelper->m_shapeIndex,
  1980. m_multiThreadedHelper->m_position,
  1981. m_multiThreadedHelper->m_quaternion,
  1982. m_multiThreadedHelper->m_color,
  1983. m_multiThreadedHelper->m_scaling);
  1984. m_multiThreadedHelper->mainThreadRelease();
  1985. break;
  1986. }
  1987. case eGUIHelperRemoveAllGraphicsInstances:
  1988. {
  1989. B3_PROFILE("eGUIHelperRemoveAllGraphicsInstances");
  1990. #ifdef BT_ENABLE_VR
  1991. if (m_tinyVrGui)
  1992. {
  1993. delete m_tinyVrGui;
  1994. m_tinyVrGui = 0;
  1995. }
  1996. #endif //BT_ENABLE_VR
  1997. m_multiThreadedHelper->m_childGuiHelper->removeAllGraphicsInstances();
  1998. if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
  1999. {
  2000. int numRenderInstances;
  2001. numRenderInstances = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
  2002. b3Assert(numRenderInstances == 0);
  2003. }
  2004. m_multiThreadedHelper->mainThreadRelease();
  2005. break;
  2006. }
  2007. case eGUIHelperRemoveGraphicsInstance:
  2008. {
  2009. B3_PROFILE("eGUIHelperRemoveGraphicsInstance");
  2010. m_multiThreadedHelper->m_childGuiHelper->removeGraphicsInstance(m_multiThreadedHelper->m_graphicsInstanceRemove);
  2011. m_multiThreadedHelper->mainThreadRelease();
  2012. break;
  2013. }
  2014. case eGUIHelperGetShapeIndexFromInstance:
  2015. {
  2016. B3_PROFILE("eGUIHelperGetShapeIndexFromInstance");
  2017. m_multiThreadedHelper->getShapeIndex_shapeIndex = m_multiThreadedHelper->m_childGuiHelper->getShapeIndexFromInstance(m_multiThreadedHelper->m_getShapeIndex_instance);
  2018. m_multiThreadedHelper->mainThreadRelease();
  2019. break;
  2020. }
  2021. case eGUIHelperChangeGraphicsInstanceTextureId:
  2022. {
  2023. B3_PROFILE("eGUIHelperChangeGraphicsInstanceTextureId");
  2024. m_multiThreadedHelper->m_childGuiHelper->replaceTexture(
  2025. m_multiThreadedHelper->m_graphicsInstanceChangeTextureShapeIndex,
  2026. m_multiThreadedHelper->m_graphicsInstanceChangeTextureId);
  2027. m_multiThreadedHelper->mainThreadRelease();
  2028. break;
  2029. }
  2030. case eGUIHelperChangeTexture:
  2031. {
  2032. B3_PROFILE("eGUIHelperChangeTexture");
  2033. m_multiThreadedHelper->m_childGuiHelper->changeTexture(
  2034. m_multiThreadedHelper->m_changeTextureUniqueId,
  2035. m_multiThreadedHelper->m_changeTextureRgbTexels,
  2036. m_multiThreadedHelper->m_changeTextureWidth,
  2037. m_multiThreadedHelper->m_changeTextureHeight);
  2038. m_multiThreadedHelper->mainThreadRelease();
  2039. break;
  2040. }
  2041. case eGUIHelperChangeGraphicsInstanceRGBAColor:
  2042. {
  2043. B3_PROFILE("eGUIHelperChangeGraphicsInstanceRGBAColor");
  2044. m_multiThreadedHelper->m_childGuiHelper->changeRGBAColor(m_multiThreadedHelper->m_graphicsInstanceChangeColor, m_multiThreadedHelper->m_rgbaColor);
  2045. m_multiThreadedHelper->mainThreadRelease();
  2046. break;
  2047. }
  2048. case eGUIHelperChangeGraphicsInstanceFlags:
  2049. {
  2050. m_multiThreadedHelper->m_childGuiHelper->changeInstanceFlags(m_multiThreadedHelper->m_graphicsInstanceFlagsInstanceUid, m_multiThreadedHelper->m_graphicsInstanceFlags);
  2051. m_multiThreadedHelper->mainThreadRelease();
  2052. break;
  2053. }
  2054. case eGUIHelperSetRgbBackground:
  2055. {
  2056. m_multiThreadedHelper->m_childGuiHelper->setBackgroundColor(m_multiThreadedHelper->m_rgbBackground);
  2057. m_multiThreadedHelper->mainThreadRelease();
  2058. break;
  2059. }
  2060. case eGUIHelperChangeGraphicsInstanceScaling:
  2061. {
  2062. B3_PROFILE("eGUIHelperChangeGraphicsInstanceScaling");
  2063. m_multiThreadedHelper->m_childGuiHelper->changeScaling(m_multiThreadedHelper->m_graphicsInstanceChangeScaling, m_multiThreadedHelper->m_baseScaling);
  2064. m_multiThreadedHelper->mainThreadRelease();
  2065. break;
  2066. }
  2067. case eGUIHelperChangeGraphicsInstanceSpecularColor:
  2068. {
  2069. B3_PROFILE("eGUIHelperChangeGraphicsInstanceSpecularColor");
  2070. m_multiThreadedHelper->m_childGuiHelper->changeSpecularColor(m_multiThreadedHelper->m_graphicsInstanceChangeSpecular, m_multiThreadedHelper->m_specularColor);
  2071. m_multiThreadedHelper->mainThreadRelease();
  2072. break;
  2073. }
  2074. case eGUIHelperDisplayCameraImageData:
  2075. {
  2076. B3_PROFILE("eGUIHelperDisplayCameraImageData");
  2077. if (m_canvas)
  2078. {
  2079. int numBytesPerPixel = 4;
  2080. int startRGBIndex = m_multiThreadedHelper->m_startPixelIndex * numBytesPerPixel;
  2081. int endRGBIndex = startRGBIndex + (*m_multiThreadedHelper->m_numPixelsCopied * numBytesPerPixel);
  2082. int startDepthIndex = m_multiThreadedHelper->m_startPixelIndex;
  2083. int endDepthIndex = startDepthIndex + (*m_multiThreadedHelper->m_numPixelsCopied);
  2084. int startSegIndex = m_multiThreadedHelper->m_startPixelIndex;
  2085. int endSegIndex = startSegIndex + (*m_multiThreadedHelper->m_numPixelsCopied);
  2086. //btScalar frustumZNear = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]-1);
  2087. //btScalar frustumZFar = m_multiThreadedHelper->m_projectionMatrix[14]/(m_multiThreadedHelper->m_projectionMatrix[10]+1);
  2088. for (int i = 0; i < gCamVisualizerWidth; i++)
  2089. {
  2090. for (int j = 0; j < gCamVisualizerHeight; j++)
  2091. {
  2092. int xIndex = int(float(i) * (float(m_multiThreadedHelper->m_destinationWidth) / float(gCamVisualizerWidth)));
  2093. int yIndex = int(float(j) * (float(m_multiThreadedHelper->m_destinationHeight) / float(gCamVisualizerHeight)));
  2094. btClamp(xIndex, 0, m_multiThreadedHelper->m_destinationWidth);
  2095. btClamp(yIndex, 0, m_multiThreadedHelper->m_destinationHeight);
  2096. int bytesPerPixel = 4; //RGBA
  2097. if (m_canvasRGBIndex >= 0)
  2098. {
  2099. int rgbPixelIndex = (xIndex + yIndex * m_multiThreadedHelper->m_destinationWidth) * bytesPerPixel;
  2100. if (rgbPixelIndex >= startRGBIndex && rgbPixelIndex < endRGBIndex)
  2101. {
  2102. m_canvas->setPixel(m_canvasRGBIndex, i, j,
  2103. m_multiThreadedHelper->m_pixelsRGBA[rgbPixelIndex - startRGBIndex],
  2104. m_multiThreadedHelper->m_pixelsRGBA[rgbPixelIndex + 1 - startRGBIndex],
  2105. m_multiThreadedHelper->m_pixelsRGBA[rgbPixelIndex + 2 - startRGBIndex],
  2106. 255); //alpha set to 255
  2107. }
  2108. }
  2109. if (m_canvasDepthIndex >= 0 && 0 != m_multiThreadedHelper->m_depthBuffer)
  2110. {
  2111. int depthPixelIndex = (xIndex + yIndex * m_multiThreadedHelper->m_destinationWidth);
  2112. if (depthPixelIndex >= startDepthIndex && depthPixelIndex < endDepthIndex)
  2113. {
  2114. float depthValue = m_multiThreadedHelper->m_depthBuffer[depthPixelIndex - startDepthIndex];
  2115. //todo: rescale the depthValue to [0..255]
  2116. if (depthValue > -1e20)
  2117. {
  2118. int rgb = 0;
  2119. btScalar frustumZNear = 0.1;
  2120. btScalar frustumZFar = 30;
  2121. btScalar minDepthValue = frustumZNear; //todo: compute more reasonably min/max depth range
  2122. btScalar maxDepthValue = frustumZFar;
  2123. float depth = depthValue;
  2124. btScalar linearDepth = 255. * (2.0 * frustumZNear) / (frustumZFar + frustumZNear - depth * (frustumZFar - frustumZNear));
  2125. btClamp(linearDepth, btScalar(0), btScalar(255));
  2126. rgb = linearDepth;
  2127. m_canvas->setPixel(m_canvasDepthIndex, i, j,
  2128. rgb,
  2129. rgb,
  2130. 255, 255); //alpha set to 255
  2131. }
  2132. else
  2133. {
  2134. m_canvas->setPixel(m_canvasDepthIndex, i, j,
  2135. 0,
  2136. 0,
  2137. 0, 255); //alpha set to 255
  2138. }
  2139. }
  2140. }
  2141. if (m_canvasSegMaskIndex >= 0 && (0 != m_multiThreadedHelper->m_segmentationMaskBuffer))
  2142. {
  2143. int segmentationMaskPixelIndex = (xIndex + yIndex * m_multiThreadedHelper->m_destinationWidth);
  2144. if (segmentationMaskPixelIndex >= startSegIndex && segmentationMaskPixelIndex < endSegIndex)
  2145. {
  2146. int segmentationMask = m_multiThreadedHelper->m_segmentationMaskBuffer[segmentationMaskPixelIndex - startSegIndex];
  2147. btVector4 palette[4] = {btVector4(32, 255, 32, 255),
  2148. btVector4(32, 32, 255, 255),
  2149. btVector4(255, 255, 32, 255),
  2150. btVector4(32, 255, 255, 255)};
  2151. if (segmentationMask >= 0)
  2152. {
  2153. int obIndex = segmentationMask & ((1 << 24) - 1);
  2154. int linkIndex = (segmentationMask >> 24) - 1;
  2155. btVector4 rgb = palette[(obIndex + linkIndex) & 3];
  2156. m_canvas->setPixel(m_canvasSegMaskIndex, i, j,
  2157. rgb.x(),
  2158. rgb.y(),
  2159. rgb.z(), 255); //alpha set to 255
  2160. }
  2161. else
  2162. {
  2163. m_canvas->setPixel(m_canvasSegMaskIndex, i, j,
  2164. 0,
  2165. 0,
  2166. 0, 255); //alpha set to 255
  2167. }
  2168. }
  2169. }
  2170. }
  2171. }
  2172. if (m_canvasRGBIndex >= 0)
  2173. m_canvas->refreshImageData(m_canvasRGBIndex);
  2174. if (m_canvasDepthIndex >= 0)
  2175. m_canvas->refreshImageData(m_canvasDepthIndex);
  2176. if (m_canvasSegMaskIndex >= 0)
  2177. m_canvas->refreshImageData(m_canvasSegMaskIndex);
  2178. }
  2179. m_multiThreadedHelper->mainThreadRelease();
  2180. break;
  2181. }
  2182. case eGUIHelperCopyCameraImageData:
  2183. {
  2184. B3_PROFILE("eGUIHelperCopyCameraImageData");
  2185. if (m_multiThreadedHelper->m_startPixelIndex == 0)
  2186. {
  2187. m_physicsServer.syncPhysicsToGraphics();
  2188. }
  2189. m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
  2190. m_multiThreadedHelper->m_projectionMatrix,
  2191. m_multiThreadedHelper->m_pixelsRGBA,
  2192. m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
  2193. m_multiThreadedHelper->m_depthBuffer,
  2194. m_multiThreadedHelper->m_depthBufferSizeInPixels,
  2195. m_multiThreadedHelper->m_segmentationMaskBuffer,
  2196. m_multiThreadedHelper->m_segmentationMaskBufferSizeInPixels,
  2197. m_multiThreadedHelper->m_startPixelIndex,
  2198. m_multiThreadedHelper->m_destinationWidth,
  2199. m_multiThreadedHelper->m_destinationHeight,
  2200. m_multiThreadedHelper->m_numPixelsCopied);
  2201. m_multiThreadedHelper->mainThreadRelease();
  2202. break;
  2203. }
  2204. case eGUIHelperResetCamera:
  2205. {
  2206. m_multiThreadedHelper->m_childGuiHelper->resetCamera(
  2207. m_multiThreadedHelper->m_resetCameraCamDist,
  2208. m_multiThreadedHelper->m_resetCameraYaw,
  2209. m_multiThreadedHelper->m_resetCameraPitch,
  2210. m_multiThreadedHelper->m_resetCameraCamPosX,
  2211. m_multiThreadedHelper->m_resetCameraCamPosY,
  2212. m_multiThreadedHelper->m_resetCameraCamPosZ);
  2213. m_multiThreadedHelper->mainThreadRelease();
  2214. break;
  2215. }
  2216. case eGUIHelperAutogenerateGraphicsObjects:
  2217. {
  2218. B3_PROFILE("eGUIHelperAutogenerateGraphicsObjects");
  2219. m_multiThreadedHelper->m_childGuiHelper->autogenerateGraphicsObjects(m_multiThreadedHelper->m_dynamicsWorld);
  2220. m_multiThreadedHelper->mainThreadRelease();
  2221. break;
  2222. }
  2223. case eGUIUserDebugAddText:
  2224. {
  2225. B3_PROFILE("eGUIUserDebugAddText");
  2226. bool replaced = false;
  2227. for (int i = 0; i < m_multiThreadedHelper->m_userDebugText.size(); i++)
  2228. {
  2229. if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpText.m_itemUniqueId)
  2230. {
  2231. m_multiThreadedHelper->m_userDebugText[i] = m_multiThreadedHelper->m_tmpText;
  2232. m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_tmpText.m_itemUniqueId;
  2233. replaced = true;
  2234. }
  2235. }
  2236. if (!replaced)
  2237. {
  2238. m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
  2239. m_multiThreadedHelper->m_resultUserDebugTextUid = m_multiThreadedHelper->m_userDebugText[m_multiThreadedHelper->m_userDebugText.size() - 1].m_itemUniqueId;
  2240. }
  2241. m_multiThreadedHelper->mainThreadRelease();
  2242. break;
  2243. }
  2244. case eGUIUserDebugAddParameter:
  2245. {
  2246. B3_PROFILE("eGUIUserDebugAddParameter");
  2247. UserDebugParameter* param = new UserDebugParameter(m_multiThreadedHelper->m_tmpParam);
  2248. m_multiThreadedHelper->m_userDebugParams.push_back(param);
  2249. if (param->m_rangeMin<= param->m_rangeMax)
  2250. {
  2251. SliderParams slider(param->m_text, &param->m_value);
  2252. slider.m_minVal = param->m_rangeMin;
  2253. slider.m_maxVal = param->m_rangeMax;
  2254. if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
  2255. m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  2256. }
  2257. else
  2258. {
  2259. int buttonId = -1;
  2260. bool isTrigger = false;
  2261. ButtonParams button(param->m_text, buttonId, isTrigger);
  2262. button.m_callback = UserButtonToggle;
  2263. button.m_userPointer = param;
  2264. button.m_initialState = false;
  2265. //create a button
  2266. if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
  2267. m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->registerButtonParameter(button);
  2268. }
  2269. m_multiThreadedHelper->m_userDebugParamUid = (*m_multiThreadedHelper->m_userDebugParams[m_multiThreadedHelper->m_userDebugParams.size() - 1]).m_itemUniqueId;
  2270. //also add actual menu
  2271. m_multiThreadedHelper->mainThreadRelease();
  2272. break;
  2273. }
  2274. case eGUIUserDebugAddLine:
  2275. {
  2276. B3_PROFILE("eGUIUserDebugAddLine");
  2277. if (m_multiThreadedHelper->m_tmpLine.m_replaceItemUid >= 0)
  2278. {
  2279. for (int i = 0; i < m_multiThreadedHelper->m_userDebugLines.size(); i++)
  2280. {
  2281. if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpLine.m_replaceItemUid)
  2282. {
  2283. m_multiThreadedHelper->m_userDebugLines[i] = m_multiThreadedHelper->m_tmpLine;
  2284. m_multiThreadedHelper->m_resultDebugLineUid = m_multiThreadedHelper->m_tmpLine.m_replaceItemUid;
  2285. }
  2286. }
  2287. }
  2288. else
  2289. {
  2290. m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
  2291. m_multiThreadedHelper->m_resultDebugLineUid = m_multiThreadedHelper->m_userDebugLines[m_multiThreadedHelper->m_userDebugLines.size() - 1].m_itemUniqueId;
  2292. }
  2293. m_multiThreadedHelper->mainThreadRelease();
  2294. break;
  2295. }
  2296. case eGUIUserDebugAddPoints:
  2297. {
  2298. B3_PROFILE("eGUIUserDebugAddPoints");
  2299. if (m_multiThreadedHelper->m_tmpPoint.m_replaceItemUid >= 0)
  2300. {
  2301. for (int i = 0; i < m_multiThreadedHelper->m_userDebugPoints.size(); i++)
  2302. {
  2303. if (m_multiThreadedHelper->m_userDebugPoints[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpPoint.m_replaceItemUid)
  2304. {
  2305. m_multiThreadedHelper->m_userDebugPoints[i] = m_multiThreadedHelper->m_tmpPoint;
  2306. m_multiThreadedHelper->m_resultDebugPointUid = m_multiThreadedHelper->m_tmpPoint.m_replaceItemUid;
  2307. }
  2308. }
  2309. }
  2310. else
  2311. {
  2312. m_multiThreadedHelper->m_userDebugPoints.push_back(m_multiThreadedHelper->m_tmpPoint);
  2313. m_multiThreadedHelper->m_resultDebugPointUid = m_multiThreadedHelper->m_userDebugPoints[m_multiThreadedHelper->m_userDebugPoints.size() - 1].m_itemUniqueId;
  2314. }
  2315. m_multiThreadedHelper->mainThreadRelease();
  2316. break;
  2317. }
  2318. case eGUIUserDebugRemoveItem:
  2319. {
  2320. B3_PROFILE("eGUIUserDebugRemoveItem");
  2321. for (int i = 0; i < m_multiThreadedHelper->m_userDebugLines.size(); i++)
  2322. {
  2323. if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
  2324. {
  2325. m_multiThreadedHelper->m_userDebugLines.swap(i, m_multiThreadedHelper->m_userDebugLines.size() - 1);
  2326. m_multiThreadedHelper->m_userDebugLines.pop_back();
  2327. break;
  2328. }
  2329. }
  2330. for (int i = 0; i < m_multiThreadedHelper->m_userDebugPoints.size(); i++)
  2331. {
  2332. if (m_multiThreadedHelper->m_userDebugPoints[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
  2333. {
  2334. m_multiThreadedHelper->m_userDebugPoints.swap(i, m_multiThreadedHelper->m_userDebugPoints.size() - 1);
  2335. m_multiThreadedHelper->m_userDebugPoints.pop_back();
  2336. break;
  2337. }
  2338. }
  2339. for (int i = 0; i < m_multiThreadedHelper->m_userDebugText.size(); i++)
  2340. {
  2341. if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
  2342. {
  2343. m_multiThreadedHelper->m_userDebugText.swap(i, m_multiThreadedHelper->m_userDebugText.size() - 1);
  2344. m_multiThreadedHelper->m_userDebugText.pop_back();
  2345. break;
  2346. }
  2347. }
  2348. m_multiThreadedHelper->mainThreadRelease();
  2349. break;
  2350. }
  2351. case eGUIUserDebugRemoveAllParameters:
  2352. {
  2353. B3_PROFILE("eGUIUserDebugRemoveAllParameters");
  2354. if (m_multiThreadedHelper->m_childGuiHelper->getParameterInterface())
  2355. m_multiThreadedHelper->m_childGuiHelper->getParameterInterface()->removeAllParameters();
  2356. for (int i = 0; i < m_multiThreadedHelper->m_userDebugParams.size(); i++)
  2357. {
  2358. delete m_multiThreadedHelper->m_userDebugParams[i];
  2359. }
  2360. m_multiThreadedHelper->m_userDebugParams.clear();
  2361. m_multiThreadedHelper->mainThreadRelease();
  2362. break;
  2363. }
  2364. case eGUIUserDebugRemoveAllItems:
  2365. {
  2366. B3_PROFILE("eGUIUserDebugRemoveAllItems");
  2367. m_multiThreadedHelper->m_userDebugLines.clear();
  2368. m_multiThreadedHelper->m_userDebugText.clear();
  2369. m_multiThreadedHelper->m_uidGenerator = 0;
  2370. m_multiThreadedHelper->mainThreadRelease();
  2371. break;
  2372. }
  2373. case eGUIDumpFramesToVideo:
  2374. {
  2375. B3_PROFILE("eGUIDumpFramesToVideo");
  2376. m_multiThreadedHelper->m_childGuiHelper->dumpFramesToVideo(m_multiThreadedHelper->m_mp4FileName);
  2377. m_multiThreadedHelper->mainThreadRelease();
  2378. break;
  2379. }
  2380. case eGUIHelperIdle:
  2381. {
  2382. break;
  2383. }
  2384. default:
  2385. {
  2386. btAssert(0);
  2387. }
  2388. }
  2389. }
  2390. void PhysicsServerExample::stepSimulation(float deltaTime)
  2391. {
  2392. BT_PROFILE("PhysicsServerExample::stepSimulation");
  2393. //this->m_physicsServer.processClientCommands();
  2394. for (int i = m_multiThreadedHelper->m_userDebugLines.size() - 1; i >= 0; i--)
  2395. {
  2396. if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
  2397. {
  2398. m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
  2399. if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime <= 0)
  2400. {
  2401. m_multiThreadedHelper->m_userDebugLines.swap(i, m_multiThreadedHelper->m_userDebugLines.size() - 1);
  2402. m_multiThreadedHelper->m_userDebugLines.pop_back();
  2403. }
  2404. }
  2405. }
  2406. for (int i = m_multiThreadedHelper->m_userDebugText.size() - 1; i >= 0; i--)
  2407. {
  2408. if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
  2409. {
  2410. m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
  2411. if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime <= 0)
  2412. {
  2413. m_multiThreadedHelper->m_userDebugText.swap(i, m_multiThreadedHelper->m_userDebugText.size() - 1);
  2414. m_multiThreadedHelper->m_userDebugText.pop_back();
  2415. }
  2416. }
  2417. }
  2418. updateGraphics();
  2419. {
  2420. if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
  2421. {
  2422. m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->writeTransforms();
  2423. }
  2424. }
  2425. }
  2426. static float vrOffset[16] = {1, 0, 0, 0,
  2427. 0, 1, 0, 0,
  2428. 0, 0, 1, 0,
  2429. 0, 0, 0, 0};
  2430. extern int gDroppedSimulationSteps;
  2431. extern int gNumSteps;
  2432. extern double gDtInSec;
  2433. extern double gSubStep;
  2434. extern btTransform gVRTrackingObjectTr;
  2435. void PhysicsServerExample::drawUserDebugLines()
  2436. {
  2437. //static char line0[1024];
  2438. //static char line1[1024];
  2439. //draw all user-debug-lines
  2440. //add array of lines
  2441. //draw all user- 'text3d' messages
  2442. if (m_multiThreadedHelper)
  2443. {
  2444. //if gBatchUserDebugLines is true, batch lines based on color+width, to reduce line draw calls
  2445. btAlignedObjectArray<btAlignedObjectArray<unsigned int> > sortedIndices;
  2446. btAlignedObjectArray<btAlignedObjectArray<btVector3FloatData> > sortedLines;
  2447. btHashMap<ColorWidth, int> hashedLines;
  2448. for (int i = 0; i < m_multiThreadedHelper->m_userDebugLines.size(); i++)
  2449. {
  2450. btVector3 from;
  2451. from.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
  2452. m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
  2453. m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
  2454. btVector3 toX;
  2455. toX.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
  2456. m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
  2457. m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
  2458. int graphicsIndex = m_multiThreadedHelper->m_userDebugLines[i].m_trackingVisualShapeIndex;
  2459. if (graphicsIndex >= 0)
  2460. {
  2461. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  2462. if (renderer)
  2463. {
  2464. float parentPos[3];
  2465. float parentOrn[4];
  2466. if (renderer->readSingleInstanceTransformToCPU(parentPos, parentOrn, graphicsIndex))
  2467. {
  2468. btTransform parentTrans;
  2469. parentTrans.setOrigin(btVector3(parentPos[0], parentPos[1], parentPos[2]));
  2470. parentTrans.setRotation(btQuaternion(parentOrn[0], parentOrn[1], parentOrn[2], parentOrn[3]));
  2471. from = parentTrans * from;
  2472. toX = parentTrans * toX;
  2473. }
  2474. }
  2475. }
  2476. btVector3 color;
  2477. color.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
  2478. m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
  2479. m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
  2480. ColorWidth cw;
  2481. color.serializeFloat(cw.m_color);
  2482. cw.width = m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth;
  2483. int index = -1;
  2484. if (gBatchUserDebugLines)
  2485. {
  2486. int* indexPtr = hashedLines.find(cw);
  2487. if (indexPtr)
  2488. {
  2489. index = *indexPtr;
  2490. }
  2491. else
  2492. {
  2493. index = sortedLines.size();
  2494. sortedLines.expand();
  2495. sortedIndices.expand();
  2496. hashedLines.insert(cw, index);
  2497. }
  2498. btAssert(index >= 0);
  2499. if (index >= 0)
  2500. {
  2501. btVector3FloatData from1, toX1;
  2502. sortedIndices[index].push_back(sortedLines[index].size());
  2503. from.serializeFloat(from1);
  2504. sortedLines[index].push_back(from1);
  2505. sortedIndices[index].push_back(sortedLines[index].size());
  2506. toX.serializeFloat(toX1);
  2507. sortedLines[index].push_back(toX1);
  2508. }
  2509. }
  2510. else
  2511. {
  2512. m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
  2513. }
  2514. }
  2515. if (gBatchUserDebugLines)
  2516. {
  2517. for (int i = 0; i < hashedLines.size(); i++)
  2518. {
  2519. ColorWidth cw = hashedLines.getKeyAtIndex(i);
  2520. int index = *hashedLines.getAtIndex(i);
  2521. int stride = sizeof(btVector3FloatData);
  2522. const float* positions = &sortedLines[index][0].m_floats[0];
  2523. int numPoints = sortedLines[index].size();
  2524. const unsigned int* indices = &sortedIndices[index][0];
  2525. int numIndices = sortedIndices[index].size();
  2526. m_guiHelper->getAppInterface()->m_renderer->drawLines(positions, cw.m_color.m_floats, numPoints, stride, indices, numIndices, cw.width);
  2527. }
  2528. }
  2529. for (int i = 0; i < m_multiThreadedHelper->m_userDebugText.size(); i++)
  2530. {
  2531. //int optionFlag = 0;//CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera|CommonGraphicsApp::eDrawText3D_TrueType;
  2532. //int optionFlag = CommonGraphicsApp::eDrawText3D_TrueType;
  2533. float orientation[4] = {0, 0, 0, 1};
  2534. //int optionFlag = CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera;
  2535. int optionFlag = 0;
  2536. if (m_multiThreadedHelper->m_userDebugText[i].m_optionFlags & CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
  2537. {
  2538. optionFlag |= CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera;
  2539. }
  2540. else
  2541. {
  2542. orientation[0] = (float)m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[0];
  2543. orientation[1] = (float)m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[1];
  2544. orientation[2] = (float)m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[2];
  2545. orientation[3] = (float)m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[3];
  2546. optionFlag |= CommonGraphicsApp::eDrawText3D_TrueType;
  2547. }
  2548. float colorRGBA[4] = {
  2549. (float)m_multiThreadedHelper->m_userDebugText[i].m_textColorRGB[0],
  2550. (float)m_multiThreadedHelper->m_userDebugText[i].m_textColorRGB[1],
  2551. (float)m_multiThreadedHelper->m_userDebugText[i].m_textColorRGB[2],
  2552. (float)1.};
  2553. float pos[3] = {(float)m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ1[0],
  2554. (float)m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ1[1],
  2555. (float)m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ1[2]};
  2556. int graphicsIndex = m_multiThreadedHelper->m_userDebugText[i].m_trackingVisualShapeIndex;
  2557. if (graphicsIndex >= 0)
  2558. {
  2559. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  2560. if (renderer)
  2561. {
  2562. float parentPos[3];
  2563. float parentOrn[4];
  2564. if (renderer->readSingleInstanceTransformToCPU(parentPos, parentOrn, graphicsIndex))
  2565. {
  2566. btTransform parentTrans;
  2567. parentTrans.setOrigin(btVector3(parentPos[0], parentPos[1], parentPos[2]));
  2568. parentTrans.setRotation(btQuaternion(parentOrn[0], parentOrn[1], parentOrn[2], parentOrn[3]));
  2569. btTransform childTr;
  2570. childTr.setOrigin(btVector3(pos[0], pos[1], pos[2]));
  2571. childTr.setRotation(btQuaternion(orientation[0], orientation[1], orientation[2], orientation[3]));
  2572. btTransform siteTr = parentTrans * childTr;
  2573. pos[0] = siteTr.getOrigin()[0];
  2574. pos[1] = siteTr.getOrigin()[1];
  2575. pos[2] = siteTr.getOrigin()[2];
  2576. btQuaternion siteOrn = siteTr.getRotation();
  2577. orientation[0] = siteOrn[0];
  2578. orientation[1] = siteOrn[1];
  2579. orientation[2] = siteOrn[2];
  2580. orientation[3] = siteOrn[3];
  2581. }
  2582. }
  2583. }
  2584. {
  2585. btAlignedObjectArray<std::string> pieces;
  2586. btAlignedObjectArray<std::string> separators;
  2587. separators.push_back("\n");
  2588. urdfStringSplit(pieces, m_multiThreadedHelper->m_userDebugText[i].m_text, separators);
  2589. double sz = m_multiThreadedHelper->m_userDebugText[i].textSize;
  2590. btTransform tr;
  2591. tr.setIdentity();
  2592. tr.setOrigin(btVector3(pos[0], pos[1], pos[2]));
  2593. tr.setRotation(btQuaternion(orientation[0], orientation[1], orientation[2], orientation[3]));
  2594. //float newpos[3]={pos[0]-float(t)*sz,pos[1],pos[2]};
  2595. for (int t = 0; t < pieces.size(); t++)
  2596. {
  2597. btTransform offset;
  2598. offset.setIdentity();
  2599. offset.setOrigin(btVector3(0, -float(t) * sz, 0));
  2600. btTransform result = tr * offset;
  2601. float newpos[3] = {(float)result.getOrigin()[0],
  2602. (float)result.getOrigin()[1],
  2603. (float)result.getOrigin()[2]};
  2604. m_guiHelper->getAppInterface()->drawText3D(pieces[t].c_str(),
  2605. newpos, orientation, colorRGBA,
  2606. sz, optionFlag);
  2607. }
  2608. }
  2609. /*m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
  2610. m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
  2611. m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
  2612. m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
  2613. m_multiThreadedHelper->m_userDebugText[i].textSize);
  2614. */
  2615. }
  2616. for (int i = 0; i < m_multiThreadedHelper->m_userDebugPoints.size(); i++) {
  2617. const double* positions = m_multiThreadedHelper->m_userDebugPoints[i].m_debugPointPositions;
  2618. const double* colors = m_multiThreadedHelper->m_userDebugPoints[i].m_debugPointColors;
  2619. const int pointNum = m_multiThreadedHelper->m_userDebugPoints[i].m_debugPointNum;
  2620. const double sz = m_multiThreadedHelper->m_userDebugPoints[i].m_pointSize;
  2621. float* pos = (float*)malloc(pointNum * 3 * sizeof(float));
  2622. float* clr = (float*)malloc(pointNum * 4 * sizeof(float));
  2623. for (int i = 0; i < pointNum; i++) {
  2624. pos[i * 3 + 0] = (float)positions[i * 3 + 0];
  2625. pos[i * 3 + 1] = (float)positions[i * 3 + 1];
  2626. pos[i * 3 + 2] = (float)positions[i * 3 + 2];
  2627. clr[i * 4 + 0] = (float)colors[i * 3 + 0];
  2628. clr[i * 4 + 1] = (float)colors[i * 3 + 1];
  2629. clr[i * 4 + 2] = (float)colors[i * 3 + 2];
  2630. clr[i * 4 + 3] = 1.f;
  2631. }
  2632. m_guiHelper->getAppInterface()->m_renderer->drawPoints(pos, clr, pointNum, 3 * sizeof(float), sz);
  2633. free(pos);
  2634. free(clr);
  2635. }
  2636. }
  2637. }
  2638. void PhysicsServerExample::renderScene()
  2639. {
  2640. m_renderedFrames++;
  2641. btTransform vrTrans;
  2642. B3_PROFILE("PhysicsServerExample::RenderScene");
  2643. if (m_physicsServer.isRealTimeSimulationEnabled())
  2644. {
  2645. static int frameCount = 0;
  2646. static btScalar prevTime = m_clock.getTimeSeconds();
  2647. frameCount++;
  2648. static char line0[1024] = {0};
  2649. static char line1[1024] = {0};
  2650. #if 0
  2651. static btScalar worseFps = 1000000;
  2652. int numFrames = 200;
  2653. static int count = 0;
  2654. count++;
  2655. if (0 == (count & 1))
  2656. {
  2657. btScalar curTime = m_clock.getTimeSeconds();
  2658. btScalar fps = 1. / (curTime - prevTime);
  2659. prevTime = curTime;
  2660. if (fps < worseFps)
  2661. {
  2662. worseFps = fps;
  2663. }
  2664. if (count > numFrames)
  2665. {
  2666. count = 0;
  2667. sprintf(line0, "fps:%f frame:%d", worseFps, frameCount / 2);
  2668. sprintf(line1, "drop:%d tscale:%f dt:%f, substep %f)", gDroppedSimulationSteps, simTimeScalingFactor,gDtInSec, gSubStep);
  2669. gDroppedSimulationSteps = 0;
  2670. worseFps = 1000000;
  2671. }
  2672. }
  2673. #endif
  2674. #ifdef BT_ENABLE_VR
  2675. if ((gInternalSimFlags & 2) && m_tinyVrGui == 0)
  2676. {
  2677. ComboBoxParams comboParams;
  2678. comboParams.m_comboboxId = 0;
  2679. comboParams.m_numItems = 0;
  2680. comboParams.m_startItem = 0;
  2681. comboParams.m_callback = 0; //MyComboBoxCallback;
  2682. comboParams.m_userPointer = 0; //this;
  2683. m_tinyVrGui = new TinyVRGui(comboParams, this->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface());
  2684. m_tinyVrGui->init();
  2685. }
  2686. if (m_tinyVrGui)
  2687. {
  2688. b3Transform tr;
  2689. tr.setIdentity();
  2690. btVector3 VRController2Pos = m_physicsServer.getVRTeleportPosition();
  2691. btQuaternion VRController2Orn = m_physicsServer.getVRTeleportOrientation();
  2692. tr.setOrigin(b3MakeVector3(VRController2Pos[0], VRController2Pos[1], VRController2Pos[2]));
  2693. tr.setRotation(b3Quaternion(VRController2Orn[0], VRController2Orn[1], VRController2Orn[2], VRController2Orn[3]));
  2694. tr = tr * b3Transform(b3Quaternion(0, 0, -SIMD_HALF_PI), b3MakeVector3(0, 0, 0));
  2695. b3Scalar dt = 0.01;
  2696. m_tinyVrGui->clearTextArea();
  2697. m_tinyVrGui->grapicalPrintf(line0, 0, 0, 0, 0, 0, 255);
  2698. m_tinyVrGui->grapicalPrintf(line1, 0, 16, 255, 255, 255, 255);
  2699. m_tinyVrGui->tick(dt, tr);
  2700. }
  2701. #endif //BT_ENABLE_VR
  2702. }
  2703. ///debug rendering
  2704. //m_args[0].m_cs->lock();
  2705. //gVRTeleportPos[0] += 0.01;
  2706. btTransform tr2a, tr2;
  2707. tr2a.setIdentity();
  2708. tr2.setIdentity();
  2709. tr2.setOrigin(m_physicsServer.getVRTeleportPosition());
  2710. tr2a.setRotation(m_physicsServer.getVRTeleportOrientation());
  2711. btTransform trTotal = tr2 * tr2a;
  2712. btTransform trInv = trTotal.inverse();
  2713. btMatrix3x3 vrOffsetRot;
  2714. vrOffsetRot.setRotation(trInv.getRotation());
  2715. for (int i = 0; i < 3; i++)
  2716. {
  2717. for (int j = 0; j < 3; j++)
  2718. {
  2719. vrOffset[i + 4 * j] = vrOffsetRot[i][j];
  2720. }
  2721. }
  2722. vrOffset[12] = trInv.getOrigin()[0];
  2723. vrOffset[13] = trInv.getOrigin()[1];
  2724. vrOffset[14] = trInv.getOrigin()[2];
  2725. if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
  2726. {
  2727. m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getActiveCamera()->setVRCameraOffsetTransform(vrOffset);
  2728. }
  2729. if (gEnableRendering)
  2730. {
  2731. int renderFlags = 0;
  2732. if (!gEnableSyncPhysicsRendering)
  2733. {
  2734. renderFlags |= 1; //COV_DISABLE_SYNC_RENDERING;
  2735. }
  2736. m_physicsServer.renderScene(renderFlags);
  2737. }
  2738. if (gEnablePicking)
  2739. {
  2740. for (int i = 0; i < MAX_VR_CONTROLLERS; i++)
  2741. {
  2742. if (m_args[0].m_isVrControllerPicking[i] || m_args[0].m_isVrControllerDragging[i])
  2743. {
  2744. btVector3 from = m_args[0].m_vrControllerPos[i];
  2745. btMatrix3x3 mat(m_args[0].m_vrControllerOrn[i]);
  2746. btVector3 toX = from + mat.getColumn(0);
  2747. btVector3 toY = from + mat.getColumn(1);
  2748. btVector3 toZ = from + mat.getColumn(2);
  2749. int width = 2;
  2750. btVector4 color;
  2751. color = btVector4(1, 0, 0, 1);
  2752. m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, width);
  2753. color = btVector4(0, 1, 0, 1);
  2754. m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toY, color, width);
  2755. color = btVector4(0, 0, 1, 1);
  2756. m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toZ, color, width);
  2757. }
  2758. }
  2759. }
  2760. if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
  2761. {
  2762. if (!m_physicsServer.isRealTimeSimulationEnabled() && !gActivedVRRealTimeSimulation)
  2763. {
  2764. //only activate real-time simulation once (for backward compatibility)
  2765. gActivedVRRealTimeSimulation = true;
  2766. m_physicsServer.enableRealTimeSimulation(1);
  2767. }
  2768. }
  2769. drawUserDebugLines();
  2770. //m_args[0].m_cs->unlock();
  2771. }
  2772. void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
  2773. {
  2774. m_renderedFrames++;
  2775. if (gEnableSyncPhysicsRendering)
  2776. {
  2777. m_physicsServer.syncPhysicsToGraphics();
  2778. }
  2779. drawUserDebugLines();
  2780. if (gEnableRendering)
  2781. {
  2782. ///debug rendering
  2783. //m_physicsServer.physicsDebugDraw(debugDrawFlags);
  2784. m_args[0].m_csGUI->lock();
  2785. //draw stuff and flush?
  2786. this->m_multiThreadedHelper->m_debugDraw->drawDebugDrawerLines();
  2787. m_args[0].m_debugDrawFlags = debugDrawFlags;
  2788. m_args[0].m_enableUpdateDebugDrawLines = true;
  2789. m_args[0].m_csGUI->unlock();
  2790. }
  2791. }
  2792. btVector3 PhysicsServerExample::getRayTo(int x, int y)
  2793. {
  2794. CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
  2795. if (!renderer)
  2796. {
  2797. btAssert(0);
  2798. return btVector3(0, 0, 0);
  2799. }
  2800. float top = 1.f;
  2801. float bottom = -1.f;
  2802. float nearPlane = 1.f;
  2803. float tanFov = (top - bottom) * 0.5f / nearPlane;
  2804. float fov = btScalar(2.0) * btAtan(tanFov);
  2805. btVector3 camPos, camTarget;
  2806. renderer->getActiveCamera()->getCameraPosition(camPos);
  2807. renderer->getActiveCamera()->getCameraTargetPosition(camTarget);
  2808. btVector3 rayFrom = camPos;
  2809. btVector3 rayForward = (camTarget - camPos);
  2810. rayForward.normalize();
  2811. float farPlane = 10000.f;
  2812. rayForward *= farPlane;
  2813. btVector3 rightOffset;
  2814. btVector3 cameraUp = btVector3(0, 0, 0);
  2815. cameraUp[m_guiHelper->getAppInterface()->getUpAxis()] = 1;
  2816. btVector3 vertical = cameraUp;
  2817. btVector3 hor;
  2818. hor = rayForward.cross(vertical);
  2819. hor.safeNormalize();
  2820. vertical = hor.cross(rayForward);
  2821. vertical.safeNormalize();
  2822. float tanfov = tanf(0.5f * fov);
  2823. hor *= 2.f * farPlane * tanfov;
  2824. vertical *= 2.f * farPlane * tanfov;
  2825. btScalar aspect;
  2826. float width = float(renderer->getScreenWidth());
  2827. float height = float(renderer->getScreenHeight());
  2828. aspect = width / height;
  2829. hor *= aspect;
  2830. btVector3 rayToCenter = rayFrom + rayForward;
  2831. btVector3 dHor = hor * 1.f / width;
  2832. btVector3 dVert = vertical * 1.f / height;
  2833. btVector3 rayTo = rayToCenter - 0.5f * hor + 0.5f * vertical;
  2834. rayTo += btScalar(x) * dHor;
  2835. rayTo -= btScalar(y) * dVert;
  2836. return rayTo;
  2837. }
  2838. void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4])
  2839. {
  2840. //printf("controllerId %d, button=%d\n",controllerId, button);
  2841. if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS)
  2842. return;
  2843. if (gGraspingController < 0)
  2844. {
  2845. gGraspingController = controllerId;
  2846. }
  2847. btTransform trLocal;
  2848. trLocal.setIdentity();
  2849. trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI) * btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
  2850. btTransform trOrg;
  2851. trOrg.setIdentity();
  2852. trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
  2853. trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
  2854. btTransform tr2a;
  2855. tr2a.setIdentity();
  2856. btTransform tr2;
  2857. tr2.setIdentity();
  2858. tr2.setOrigin(m_physicsServer.getVRTeleportPosition());
  2859. tr2a.setRotation(m_physicsServer.getVRTeleportOrientation());
  2860. btTransform trTotal = tr2 * tr2a * trOrg * trLocal;
  2861. if (controllerId != gGraspingController)
  2862. {
  2863. if (button == 1 && state == 0)
  2864. {
  2865. }
  2866. }
  2867. else
  2868. {
  2869. if (button == 1)
  2870. {
  2871. if (state == 1)
  2872. {
  2873. gDebugRenderToggle = 1;
  2874. }
  2875. else
  2876. {
  2877. gDebugRenderToggle = 0;
  2878. #if 0 //it confuses people, make it into a debug option in a VR GUI?
  2879. if (simTimeScalingFactor==0)
  2880. {
  2881. simTimeScalingFactor = 1;
  2882. } else
  2883. {
  2884. if (simTimeScalingFactor==1)
  2885. {
  2886. simTimeScalingFactor = 0.25;
  2887. }
  2888. else
  2889. {
  2890. simTimeScalingFactor = 0;
  2891. }
  2892. }
  2893. #endif
  2894. }
  2895. }
  2896. else
  2897. {
  2898. }
  2899. }
  2900. if (button == 32 && state == 0)
  2901. {
  2902. if (controllerId == gGraspingController)
  2903. {
  2904. }
  2905. else
  2906. {
  2907. // gEnableKukaControl = !gEnableKukaControl;
  2908. }
  2909. }
  2910. if (button == 1 && gEnableTeleporting)
  2911. {
  2912. m_args[0].m_isVrControllerTeleporting[controllerId] = true;
  2913. }
  2914. if (controllerId == gGraspingController && (button == 33))
  2915. {
  2916. }
  2917. else
  2918. {
  2919. if (button == 33 && gEnablePicking)
  2920. {
  2921. m_args[0].m_isVrControllerPicking[controllerId] = (state != 0);
  2922. m_args[0].m_isVrControllerReleasing[controllerId] = (state == 0);
  2923. }
  2924. if ((button == 33) || (button == 1))
  2925. {
  2926. // m_args[0].m_vrControllerPos[controllerId].setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
  2927. // m_args[0].m_vrControllerOrn[controllerId].setValue(orn[0], orn[1], orn[2], orn[3]);
  2928. m_args[0].m_vrControllerPos[controllerId] = trTotal.getOrigin();
  2929. m_args[0].m_vrControllerOrn[controllerId] = trTotal.getRotation();
  2930. }
  2931. }
  2932. m_args[0].m_csGUI->lock();
  2933. m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
  2934. m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_CONTROLLER;
  2935. m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
  2936. m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
  2937. m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
  2938. m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
  2939. m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
  2940. m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
  2941. m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
  2942. m_args[0].m_vrControllerEvents[controllerId].m_numButtonEvents++;
  2943. if (state)
  2944. {
  2945. m_args[0].m_vrControllerEvents[controllerId].m_buttons[button] |= eButtonIsDown + eButtonTriggered;
  2946. }
  2947. else
  2948. {
  2949. m_args[0].m_vrControllerEvents[controllerId].m_buttons[button] |= eButtonReleased;
  2950. m_args[0].m_vrControllerEvents[controllerId].m_buttons[button] &= ~eButtonIsDown;
  2951. }
  2952. m_args[0].m_csGUI->unlock();
  2953. }
  2954. void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis, float auxAnalogAxes[10])
  2955. {
  2956. if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS)
  2957. {
  2958. printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
  2959. return;
  2960. }
  2961. btTransform trLocal;
  2962. trLocal.setIdentity();
  2963. trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI) * btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
  2964. btTransform trOrg;
  2965. trOrg.setIdentity();
  2966. trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
  2967. trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
  2968. btTransform tr2a;
  2969. tr2a.setIdentity();
  2970. btTransform tr2;
  2971. tr2.setIdentity();
  2972. tr2.setOrigin(m_physicsServer.getVRTeleportPosition());
  2973. tr2a.setRotation(m_physicsServer.getVRTeleportOrientation());
  2974. btTransform trTotal = tr2 * tr2a * trOrg * trLocal;
  2975. if (controllerId == gGraspingController)
  2976. {
  2977. }
  2978. else
  2979. {
  2980. m_args[0].m_vrControllerPos[controllerId] = trTotal.getOrigin();
  2981. m_args[0].m_vrControllerOrn[controllerId] = trTotal.getRotation();
  2982. }
  2983. m_args[0].m_csGUI->lock();
  2984. m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
  2985. m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_CONTROLLER;
  2986. m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
  2987. m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
  2988. m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
  2989. m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
  2990. m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
  2991. m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
  2992. m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
  2993. m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
  2994. m_args[0].m_vrControllerEvents[controllerId].m_analogAxis = analogAxis;
  2995. for (int i = 0; i < 10; i++)
  2996. {
  2997. m_args[0].m_vrControllerEvents[controllerId].m_auxAnalogAxis[i] = auxAnalogAxes[i];
  2998. }
  2999. m_args[0].m_csGUI->unlock();
  3000. }
  3001. void PhysicsServerExample::vrHMDMoveCallback(int controllerId, float pos[4], float orn[4])
  3002. {
  3003. if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS)
  3004. {
  3005. printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
  3006. return;
  3007. }
  3008. //we may need to add some trLocal transform, to align the camera to our preferences
  3009. btTransform trLocal;
  3010. trLocal.setIdentity();
  3011. // trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
  3012. btTransform trOrg;
  3013. trOrg.setIdentity();
  3014. trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
  3015. trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
  3016. btTransform tr2a;
  3017. tr2a.setIdentity();
  3018. btTransform tr2;
  3019. tr2.setIdentity();
  3020. tr2.setOrigin(m_physicsServer.getVRTeleportPosition());
  3021. tr2a.setRotation(m_physicsServer.getVRTeleportOrientation());
  3022. btTransform trTotal = tr2 * tr2a * trOrg * trLocal;
  3023. m_args[0].m_csGUI->lock();
  3024. m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
  3025. m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_HMD;
  3026. m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
  3027. m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
  3028. m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
  3029. m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
  3030. m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
  3031. m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
  3032. m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
  3033. m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
  3034. m_args[0].m_csGUI->unlock();
  3035. }
  3036. void PhysicsServerExample::vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orn[4])
  3037. {
  3038. if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS)
  3039. {
  3040. printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
  3041. return;
  3042. }
  3043. //we may need to add some trLocal transform, to align the camera to our preferences
  3044. btTransform trLocal;
  3045. trLocal.setIdentity();
  3046. trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI) * btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
  3047. btTransform trOrg;
  3048. trOrg.setIdentity();
  3049. trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
  3050. trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
  3051. btTransform tr2a;
  3052. tr2a.setIdentity();
  3053. btTransform tr2;
  3054. tr2.setIdentity();
  3055. tr2.setOrigin(m_physicsServer.getVRTeleportPosition());
  3056. tr2a.setRotation(m_physicsServer.getVRTeleportOrientation());
  3057. btTransform trTotal = tr2 * tr2a * trOrg * trLocal;
  3058. m_args[0].m_csGUI->lock();
  3059. m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
  3060. m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_GENERIC_TRACKER;
  3061. m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
  3062. m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
  3063. m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
  3064. m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
  3065. m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
  3066. m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
  3067. m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
  3068. m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
  3069. m_args[0].m_csGUI->unlock();
  3070. }
  3071. extern int gSharedMemoryKey;
  3072. class CommonExampleInterface* PhysicsServerCreateFuncInternal(struct CommonExampleOptions& options)
  3073. {
  3074. MultiThreadedOpenGLGuiHelper* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper(options.m_guiHelper->getAppInterface(), options.m_guiHelper, options.m_skipGraphicsUpdate);
  3075. PhysicsServerExample* example = new PhysicsServerExample(guiHelperWrapper,
  3076. options.m_commandProcessorCreation,
  3077. options.m_sharedMem,
  3078. options.m_option);
  3079. if (gSharedMemoryKey >= 0)
  3080. {
  3081. example->setSharedMemoryKey(gSharedMemoryKey);
  3082. }
  3083. if (options.m_option & PHYSICS_SERVER_ENABLE_COMMAND_LOGGING)
  3084. {
  3085. example->enableCommandLogging();
  3086. }
  3087. if (options.m_option & PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG)
  3088. {
  3089. example->replayFromLogFile();
  3090. }
  3091. return example;
  3092. }