PhysicsServerCommandProcessor.cpp 145 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176317731783179318031813182318331843185318631873188318931903191319231933194319531963197319831993200320132023203320432053206320732083209321032113212321332143215321632173218321932203221322232233224322532263227322832293230323132323233323432353236323732383239324032413242324332443245324632473248324932503251325232533254325532563257325832593260326132623263326432653266326732683269327032713272327332743275327632773278327932803281328232833284328532863287328832893290329132923293329432953296329732983299330033013302330333043305330633073308330933103311331233133314331533163317331833193320332133223323332433253326332733283329333033313332333333343335333633373338333933403341334233433344334533463347334833493350335133523353335433553356335733583359336033613362336333643365336633673368336933703371337233733374337533763377337833793380338133823383338433853386338733883389339033913392339333943395339633973398339934003401340234033404340534063407340834093410341134123413341434153416341734183419342034213422342334243425342634273428342934303431343234333434343534363437343834393440344134423443344434453446344734483449345034513452345334543455345634573458345934603461346234633464346534663467346834693470347134723473347434753476347734783479348034813482348334843485348634873488348934903491349234933494349534963497349834993500350135023503350435053506350735083509351035113512351335143515351635173518351935203521352235233524352535263527352835293530353135323533353435353536353735383539354035413542354335443545354635473548354935503551355235533554355535563557355835593560356135623563356435653566356735683569357035713572357335743575357635773578357935803581358235833584358535863587358835893590359135923593359435953596359735983599360036013602360336043605360636073608360936103611361236133614361536163617361836193620362136223623362436253626362736283629363036313632363336343635363636373638363936403641
  1. #include "PhysicsServerCommandProcessor.h"
  2. #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
  3. #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
  4. #include "../Importers/ImportURDFDemo/URDF2Bullet.h"
  5. #include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
  6. #include "TinyRendererVisualShapeConverter.h"
  7. #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
  8. #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
  9. #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
  10. #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
  11. #include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h"
  12. #include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
  13. #include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
  14. #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
  15. #include "LinearMath/btHashMap.h"
  16. #include "BulletInverseDynamics/MultiBodyTree.hpp"
  17. #include "IKTrajectoryHelper.h"
  18. #include "btBulletDynamicsCommon.h"
  19. #include "LinearMath/btTransform.h"
  20. #include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
  21. #include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
  22. #include "LinearMath/btSerializer.h"
  23. #include "Bullet3Common/b3Logging.h"
  24. #include "../CommonInterfaces/CommonGUIHelperInterface.h"
  25. #include "SharedMemoryCommands.h"
  26. //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
  27. btVector3 gLastPickPos(0, 0, 0);
  28. bool gCloseToKuka=false;
  29. bool gEnableRealTimeSimVR=false;
  30. bool gCreateSamuraiRobotAssets = true;
  31. int gCreateObjectSimVR = -1;
  32. btScalar simTimeScalingFactor = 1;
  33. btScalar gRhsClamp = 1.f;
  34. struct UrdfLinkNameMapUtil
  35. {
  36. btMultiBody* m_mb;
  37. btDefaultSerializer* m_memSerializer;
  38. UrdfLinkNameMapUtil():m_mb(0),m_memSerializer(0)
  39. {
  40. }
  41. virtual ~UrdfLinkNameMapUtil()
  42. {
  43. delete m_memSerializer;
  44. }
  45. };
  46. struct SharedMemoryDebugDrawer : public btIDebugDraw
  47. {
  48. int m_debugMode;
  49. btAlignedObjectArray<SharedMemLines> m_lines2;
  50. SharedMemoryDebugDrawer ()
  51. :m_debugMode(0)
  52. {
  53. }
  54. virtual void drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color)
  55. {
  56. }
  57. virtual void reportErrorWarning(const char* warningString)
  58. {
  59. }
  60. virtual void draw3dText(const btVector3& location,const char* textString)
  61. {
  62. }
  63. virtual void setDebugMode(int debugMode)
  64. {
  65. m_debugMode = debugMode;
  66. }
  67. virtual int getDebugMode() const
  68. {
  69. return m_debugMode;
  70. }
  71. virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color)
  72. {
  73. SharedMemLines line;
  74. line.m_from = from;
  75. line.m_to = to;
  76. line.m_color = color;
  77. m_lines2.push_back(line);
  78. }
  79. };
  80. struct InteralBodyData
  81. {
  82. btMultiBody* m_multiBody;
  83. btRigidBody* m_rigidBody;
  84. int m_testData;
  85. btTransform m_rootLocalInertialFrame;
  86. btAlignedObjectArray<btTransform> m_linkLocalInertialFrames;
  87. InteralBodyData()
  88. :m_multiBody(0),
  89. m_rigidBody(0),
  90. m_testData(0)
  91. {
  92. m_rootLocalInertialFrame.setIdentity();
  93. }
  94. };
  95. ///todo: templatize this
  96. struct InternalBodyHandle : public InteralBodyData
  97. {
  98. BT_DECLARE_ALIGNED_ALLOCATOR();
  99. int m_nextFreeHandle;
  100. void SetNextFree(int next)
  101. {
  102. m_nextFreeHandle = next;
  103. }
  104. int GetNextFree() const
  105. {
  106. return m_nextFreeHandle;
  107. }
  108. };
  109. class btCommandChunk
  110. {
  111. public:
  112. int m_chunkCode;
  113. int m_length;
  114. void *m_oldPtr;
  115. int m_dna_nr;
  116. int m_number;
  117. };
  118. class bCommandChunkPtr4
  119. {
  120. public:
  121. bCommandChunkPtr4(){}
  122. int code;
  123. int len;
  124. union
  125. {
  126. int m_uniqueInt;
  127. };
  128. int dna_nr;
  129. int nr;
  130. };
  131. // ----------------------------------------------------- //
  132. class bCommandChunkPtr8
  133. {
  134. public:
  135. bCommandChunkPtr8(){}
  136. int code, len;
  137. union
  138. {
  139. int m_uniqueInts[2];
  140. };
  141. int dna_nr, nr;
  142. };
  143. struct CommandLogger
  144. {
  145. FILE* m_file;
  146. void writeHeader(unsigned char* buffer) const
  147. {
  148. #ifdef BT_USE_DOUBLE_PRECISION
  149. memcpy(buffer, "BT3CMDd", 7);
  150. #else
  151. memcpy(buffer, "BT3CMDf", 7);
  152. #endif //BT_USE_DOUBLE_PRECISION
  153. int littleEndian= 1;
  154. littleEndian= ((char*)&littleEndian)[0];
  155. if (sizeof(void*)==8)
  156. {
  157. buffer[7] = '-';
  158. } else
  159. {
  160. buffer[7] = '_';
  161. }
  162. if (littleEndian)
  163. {
  164. buffer[8]='v';
  165. } else
  166. {
  167. buffer[8]='V';
  168. }
  169. buffer[9] = 0;
  170. buffer[10] = 0;
  171. buffer[11] = 0;
  172. int ver = btGetVersion();
  173. if (ver>=0 && ver<999)
  174. {
  175. sprintf((char*)&buffer[9],"%d",ver);
  176. }
  177. }
  178. void logCommand(const SharedMemoryCommand& command)
  179. {
  180. btCommandChunk chunk;
  181. chunk.m_chunkCode = command.m_type;
  182. chunk.m_oldPtr = 0;
  183. chunk.m_dna_nr = 0;
  184. chunk.m_length = sizeof(SharedMemoryCommand);
  185. chunk.m_number = 1;
  186. fwrite((const char*)&chunk,sizeof(btCommandChunk), 1,m_file);
  187. fwrite((const char*)&command,sizeof(SharedMemoryCommand),1,m_file);
  188. }
  189. CommandLogger(const char* fileName)
  190. {
  191. m_file = fopen(fileName,"wb");
  192. unsigned char buf[15];
  193. buf[12] = 12;
  194. buf[13] = 13;
  195. buf[14] = 14;
  196. writeHeader(buf);
  197. fwrite(buf,12,1,m_file);
  198. }
  199. virtual ~CommandLogger()
  200. {
  201. fclose(m_file);
  202. }
  203. };
  204. struct CommandLogPlayback
  205. {
  206. unsigned char m_header[12];
  207. FILE* m_file;
  208. bool m_bitsVary;
  209. bool m_fileIs64bit;
  210. CommandLogPlayback(const char* fileName)
  211. {
  212. m_file = fopen(fileName,"rb");
  213. if (m_file)
  214. {
  215. fread(m_header,12,1,m_file);
  216. }
  217. unsigned char c = m_header[7];
  218. m_fileIs64bit = (c=='-');
  219. const bool VOID_IS_8 = ((sizeof(void*)==8));
  220. m_bitsVary = (VOID_IS_8 != m_fileIs64bit);
  221. }
  222. virtual ~CommandLogPlayback()
  223. {
  224. if (m_file)
  225. {
  226. fclose(m_file);
  227. m_file=0;
  228. }
  229. }
  230. bool processNextCommand(SharedMemoryCommand* cmd)
  231. {
  232. if (m_file)
  233. {
  234. size_t s = 0;
  235. if (m_fileIs64bit)
  236. {
  237. bCommandChunkPtr8 chunk8;
  238. s = fread((void*)&chunk8,sizeof(bCommandChunkPtr8),1,m_file);
  239. } else
  240. {
  241. bCommandChunkPtr4 chunk4;
  242. s = fread((void*)&chunk4,sizeof(bCommandChunkPtr4),1,m_file);
  243. }
  244. if (s==1)
  245. {
  246. s = fread(cmd,sizeof(SharedMemoryCommand),1,m_file);
  247. return (s==1);
  248. }
  249. }
  250. return false;
  251. }
  252. };
  253. struct SaveWorldObjectData
  254. {
  255. b3AlignedObjectArray<int> m_bodyUniqueIds;
  256. std::string m_fileName;
  257. };
  258. struct PhysicsServerCommandProcessorInternalData
  259. {
  260. ///handle management
  261. btAlignedObjectArray<InternalBodyHandle> m_bodyHandles;
  262. int m_numUsedHandles; // number of active handles
  263. int m_firstFreeHandle; // free handles list
  264. InternalBodyHandle* getHandle(int handle)
  265. {
  266. btAssert(handle>=0);
  267. btAssert(handle<m_bodyHandles.size());
  268. if ((handle<0) || (handle>=m_bodyHandles.size()))
  269. {
  270. return 0;
  271. }
  272. return &m_bodyHandles[handle];
  273. }
  274. const InternalBodyHandle* getHandle(int handle) const
  275. {
  276. return &m_bodyHandles[handle];
  277. }
  278. void increaseHandleCapacity(int extraCapacity)
  279. {
  280. int curCapacity = m_bodyHandles.size();
  281. btAssert(curCapacity == m_numUsedHandles);
  282. int newCapacity = curCapacity + extraCapacity;
  283. m_bodyHandles.resize(newCapacity);
  284. {
  285. for (int i = curCapacity; i < newCapacity; i++)
  286. m_bodyHandles[i].SetNextFree(i + 1);
  287. m_bodyHandles[newCapacity - 1].SetNextFree(-1);
  288. }
  289. m_firstFreeHandle = curCapacity;
  290. }
  291. void initHandles()
  292. {
  293. m_numUsedHandles = 0;
  294. m_firstFreeHandle = -1;
  295. increaseHandleCapacity(1);
  296. }
  297. void exitHandles()
  298. {
  299. m_bodyHandles.resize(0);
  300. m_firstFreeHandle = -1;
  301. m_numUsedHandles = 0;
  302. }
  303. int allocHandle()
  304. {
  305. btAssert(m_firstFreeHandle>=0);
  306. int handle = m_firstFreeHandle;
  307. m_firstFreeHandle = getHandle(handle)->GetNextFree();
  308. m_numUsedHandles++;
  309. if (m_firstFreeHandle<0)
  310. {
  311. int curCapacity = m_bodyHandles.size();
  312. int additionalCapacity= m_bodyHandles.size();
  313. increaseHandleCapacity(additionalCapacity);
  314. getHandle(handle)->SetNextFree(m_firstFreeHandle);
  315. }
  316. return handle;
  317. }
  318. void freeHandle(int handle)
  319. {
  320. btAssert(handle >= 0);
  321. getHandle(handle)->SetNextFree(m_firstFreeHandle);
  322. m_firstFreeHandle = handle;
  323. m_numUsedHandles--;
  324. }
  325. ///end handle management
  326. bool m_allowRealTimeSimulation;
  327. bool m_hasGround;
  328. btMultiBodyFixedConstraint* m_gripperRigidbodyFixed;
  329. btMultiBody* m_gripperMultiBody;
  330. btMultiBodyFixedConstraint* m_kukaGripperFixed;
  331. btMultiBody* m_kukaGripperMultiBody;
  332. btMultiBodyPoint2Point* m_kukaGripperRevolute1;
  333. btMultiBodyPoint2Point* m_kukaGripperRevolute2;
  334. int m_huskyId;
  335. int m_KukaId;
  336. int m_sphereId;
  337. int m_gripperId;
  338. CommandLogger* m_commandLogger;
  339. CommandLogPlayback* m_logPlayback;
  340. btScalar m_physicsDeltaTime;
  341. btScalar m_numSimulationSubSteps;
  342. btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks;
  343. btHashMap<btHashPtr, btInverseDynamics::MultiBodyTree*> m_inverseDynamicsBodies;
  344. btHashMap<btHashPtr, IKTrajectoryHelper*> m_inverseKinematicsHelpers;
  345. b3AlignedObjectArray<SaveWorldObjectData> m_saveWorldBodyData;
  346. btAlignedObjectArray<btBulletWorldImporter*> m_worldImporters;
  347. btAlignedObjectArray<UrdfLinkNameMapUtil*> m_urdfLinkNameMapper;
  348. btAlignedObjectArray<std::string*> m_strings;
  349. btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
  350. btBroadphaseInterface* m_broadphase;
  351. btCollisionDispatcher* m_dispatcher;
  352. btMultiBodyConstraintSolver* m_solver;
  353. btDefaultCollisionConfiguration* m_collisionConfiguration;
  354. btMultiBodyDynamicsWorld* m_dynamicsWorld;
  355. SharedMemoryDebugDrawer* m_remoteDebugDrawer;
  356. btAlignedObjectArray<b3ContactPointData> m_cachedContactPoints;
  357. btAlignedObjectArray<int> m_sdfRecentLoadedBodies;
  358. struct GUIHelperInterface* m_guiHelper;
  359. int m_sharedMemoryKey;
  360. bool m_verboseOutput;
  361. //data for picking objects
  362. class btRigidBody* m_pickedBody;
  363. class btTypedConstraint* m_pickedConstraint;
  364. class btMultiBodyPoint2Point* m_pickingMultiBodyPoint2Point;
  365. btVector3 m_oldPickingPos;
  366. btVector3 m_hitPos;
  367. btScalar m_oldPickingDist;
  368. bool m_prevCanSleep;
  369. TinyRendererVisualShapeConverter m_visualConverter;
  370. PhysicsServerCommandProcessorInternalData()
  371. :m_hasGround(false),
  372. m_gripperRigidbodyFixed(0),
  373. m_gripperMultiBody(0),
  374. m_kukaGripperFixed(0),
  375. m_kukaGripperMultiBody(0),
  376. m_kukaGripperRevolute1(0),
  377. m_kukaGripperRevolute2(0),
  378. m_allowRealTimeSimulation(false),
  379. m_huskyId(-1),
  380. m_KukaId(-1),
  381. m_sphereId(-1),
  382. m_gripperId(-1),
  383. m_commandLogger(0),
  384. m_logPlayback(0),
  385. m_physicsDeltaTime(1./240.),
  386. m_numSimulationSubSteps(0),
  387. m_dynamicsWorld(0),
  388. m_remoteDebugDrawer(0),
  389. m_guiHelper(0),
  390. m_sharedMemoryKey(SHARED_MEMORY_KEY),
  391. m_verboseOutput(false),
  392. m_pickedBody(0),
  393. m_pickedConstraint(0),
  394. m_pickingMultiBodyPoint2Point(0)
  395. {
  396. initHandles();
  397. #if 0
  398. btAlignedObjectArray<int> bla;
  399. for (int i=0;i<1024;i++)
  400. {
  401. int handle = allocHandle();
  402. bla.push_back(handle);
  403. InternalBodyHandle* body = getHandle(handle);
  404. InteralBodyData* body2 = body;
  405. }
  406. for (int i=0;i<bla.size();i++)
  407. {
  408. freeHandle(bla[i]);
  409. }
  410. bla.resize(0);
  411. for (int i=0;i<1024;i++)
  412. {
  413. int handle = allocHandle();
  414. bla.push_back(handle);
  415. InternalBodyHandle* body = getHandle(handle);
  416. InteralBodyData* body2 = body;
  417. }
  418. for (int i=0;i<bla.size();i++)
  419. {
  420. freeHandle(bla[i]);
  421. }
  422. bla.resize(0);
  423. for (int i=0;i<1024;i++)
  424. {
  425. int handle = allocHandle();
  426. bla.push_back(handle);
  427. InternalBodyHandle* body = getHandle(handle);
  428. InteralBodyData* body2 = body;
  429. }
  430. for (int i=0;i<bla.size();i++)
  431. {
  432. freeHandle(bla[i]);
  433. }
  434. #endif
  435. }
  436. btInverseDynamics::MultiBodyTree* findOrCreateTree(btMultiBody* multiBody)
  437. {
  438. btInverseDynamics::MultiBodyTree* tree = 0;
  439. btInverseDynamics::MultiBodyTree** treePtrPtr =
  440. m_inverseDynamicsBodies.find(multiBody);
  441. if (treePtrPtr)
  442. {
  443. tree = *treePtrPtr;
  444. }
  445. else
  446. {
  447. btInverseDynamics::btMultiBodyTreeCreator id_creator;
  448. if (-1 == id_creator.createFromBtMultiBody(multiBody, false))
  449. {
  450. }
  451. else
  452. {
  453. tree = btInverseDynamics::CreateMultiBodyTree(id_creator);
  454. m_inverseDynamicsBodies.insert(multiBody, tree);
  455. }
  456. }
  457. return tree;
  458. }
  459. };
  460. void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper)
  461. {
  462. if (guiHelper)
  463. {
  464. guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
  465. } else
  466. {
  467. if (m_data->m_guiHelper && m_data->m_dynamicsWorld && m_data->m_dynamicsWorld->getDebugDrawer())
  468. {
  469. m_data->m_dynamicsWorld->setDebugDrawer(0);
  470. }
  471. }
  472. m_data->m_guiHelper = guiHelper;
  473. }
  474. PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
  475. {
  476. m_data = new PhysicsServerCommandProcessorInternalData();
  477. createEmptyDynamicsWorld();
  478. m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
  479. m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
  480. }
  481. PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
  482. {
  483. deleteDynamicsWorld();
  484. if (m_data->m_commandLogger)
  485. {
  486. delete m_data->m_commandLogger;
  487. m_data->m_commandLogger = 0;
  488. }
  489. delete m_data;
  490. }
  491. void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
  492. {
  493. ///collision configuration contains default setup for memory, collision setup
  494. m_data->m_collisionConfiguration = new btDefaultCollisionConfiguration();
  495. //m_collisionConfiguration->setConvexConvexMultipointIterations();
  496. ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
  497. m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration);
  498. m_data->m_broadphase = new btDbvtBroadphase();
  499. m_data->m_solver = new btMultiBodyConstraintSolver;
  500. m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
  501. //Workaround: in a VR application, where we avoid synchronizaing between GFX/Physics threads, we don't want to resize this array, so pre-allocate it
  502. m_data->m_dynamicsWorld->getCollisionObjectArray().reserve(8192);
  503. m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
  504. m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
  505. m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
  506. }
  507. void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies()
  508. {
  509. for (int i = 0; i < m_data->m_inverseDynamicsBodies.size(); i++)
  510. {
  511. btInverseDynamics::MultiBodyTree** treePtrPtr = m_data->m_inverseDynamicsBodies.getAtIndex(i);
  512. if (treePtrPtr)
  513. {
  514. btInverseDynamics::MultiBodyTree* tree = *treePtrPtr;
  515. delete tree;
  516. }
  517. }
  518. m_data->m_inverseDynamicsBodies.clear();
  519. }
  520. void PhysicsServerCommandProcessor::deleteDynamicsWorld()
  521. {
  522. deleteCachedInverseDynamicsBodies();
  523. for (int i=0;i<m_data->m_multiBodyJointFeedbacks.size();i++)
  524. {
  525. delete m_data->m_multiBodyJointFeedbacks[i];
  526. }
  527. m_data->m_multiBodyJointFeedbacks.clear();
  528. for (int i=0;i<m_data->m_worldImporters.size();i++)
  529. {
  530. delete m_data->m_worldImporters[i];
  531. }
  532. m_data->m_worldImporters.clear();
  533. for (int i=0;i<m_data->m_urdfLinkNameMapper.size();i++)
  534. {
  535. delete m_data->m_urdfLinkNameMapper[i];
  536. }
  537. m_data->m_urdfLinkNameMapper.clear();
  538. for (int i=0;i<m_data->m_strings.size();i++)
  539. {
  540. delete m_data->m_strings[i];
  541. }
  542. m_data->m_strings.clear();
  543. btAlignedObjectArray<btTypedConstraint*> constraints;
  544. btAlignedObjectArray<btMultiBodyConstraint*> mbconstraints;
  545. if (m_data->m_dynamicsWorld)
  546. {
  547. int i;
  548. for (i = m_data->m_dynamicsWorld->getNumConstraints() - 1; i >= 0; i--)
  549. {
  550. btTypedConstraint* constraint =m_data->m_dynamicsWorld->getConstraint(i);
  551. constraints.push_back(constraint);
  552. m_data->m_dynamicsWorld->removeConstraint(constraint);
  553. }
  554. for (i=m_data->m_dynamicsWorld->getNumMultiBodyConstraints()-1;i>=0;i--)
  555. {
  556. btMultiBodyConstraint* mbconstraint = m_data->m_dynamicsWorld->getMultiBodyConstraint(i);
  557. mbconstraints.push_back(mbconstraint);
  558. m_data->m_dynamicsWorld->removeMultiBodyConstraint(mbconstraint);
  559. }
  560. for (i = m_data->m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
  561. {
  562. btCollisionObject* obj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
  563. btRigidBody* body = btRigidBody::upcast(obj);
  564. if (body && body->getMotionState())
  565. {
  566. delete body->getMotionState();
  567. }
  568. m_data->m_dynamicsWorld->removeCollisionObject(obj);
  569. delete obj;
  570. }
  571. for (i=m_data->m_dynamicsWorld->getNumMultibodies()-1;i>=0;i--)
  572. {
  573. btMultiBody* mb = m_data->m_dynamicsWorld->getMultiBody(i);
  574. m_data->m_dynamicsWorld->removeMultiBody(mb);
  575. delete mb;
  576. }
  577. }
  578. for (int i=0;i<constraints.size();i++)
  579. {
  580. delete constraints[i];
  581. }
  582. constraints.clear();
  583. for (int i=0;i<mbconstraints.size();i++)
  584. {
  585. delete mbconstraints[i];
  586. }
  587. mbconstraints.clear();
  588. //delete collision shapes
  589. for (int j = 0; j<m_data->m_collisionShapes.size(); j++)
  590. {
  591. btCollisionShape* shape = m_data->m_collisionShapes[j];
  592. delete shape;
  593. }
  594. m_data->m_collisionShapes.clear();
  595. delete m_data->m_dynamicsWorld;
  596. m_data->m_dynamicsWorld=0;
  597. delete m_data->m_remoteDebugDrawer;
  598. m_data->m_remoteDebugDrawer =0;
  599. delete m_data->m_solver;
  600. m_data->m_solver=0;
  601. delete m_data->m_broadphase;
  602. m_data->m_broadphase=0;
  603. delete m_data->m_dispatcher;
  604. m_data->m_dispatcher=0;
  605. delete m_data->m_collisionConfiguration;
  606. m_data->m_collisionConfiguration=0;
  607. }
  608. bool PhysicsServerCommandProcessor::supportsJointMotor(btMultiBody* mb, int mbLinkIndex)
  609. {
  610. bool canHaveMotor = (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute
  611. ||mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::ePrismatic);
  612. return canHaveMotor;
  613. }
  614. //for testing, create joint motors for revolute and prismatic joints
  615. void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb)
  616. {
  617. int numLinks = mb->getNumLinks();
  618. for (int i=0;i<numLinks;i++)
  619. {
  620. int mbLinkIndex = i;
  621. if (supportsJointMotor(mb,mbLinkIndex))
  622. {
  623. float maxMotorImpulse = 1.f;
  624. int dof = 0;
  625. btScalar desiredVelocity = 0.f;
  626. btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,dof,desiredVelocity,maxMotorImpulse);
  627. motor->setPositionTarget(0, 0);
  628. motor->setVelocityTarget(0, 1);
  629. //motor->setRhsClamp(gRhsClamp);
  630. //motor->setMaxAppliedImpulse(0);
  631. mb->getLink(mbLinkIndex).m_userPtr = motor;
  632. m_data->m_dynamicsWorld->addMultiBodyConstraint(motor);
  633. motor->finalizeMultiDof();
  634. }
  635. }
  636. }
  637. bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody)
  638. {
  639. btAssert(m_data->m_dynamicsWorld);
  640. if (!m_data->m_dynamicsWorld)
  641. {
  642. b3Error("loadSdf: No valid m_dynamicsWorld");
  643. return false;
  644. }
  645. m_data->m_sdfRecentLoadedBodies.clear();
  646. BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
  647. bool useFixedBase = false;
  648. bool loadOk = u2b.loadSDF(fileName, useFixedBase);
  649. if (loadOk)
  650. {
  651. for (int i=0;i<u2b.getNumAllocatedCollisionShapes();i++)
  652. {
  653. btCollisionShape* shape =u2b.getAllocatedCollisionShape(i);
  654. m_data->m_collisionShapes.push_back(shape);
  655. }
  656. btTransform rootTrans;
  657. rootTrans.setIdentity();
  658. if (m_data->m_verboseOutput)
  659. {
  660. b3Printf("loaded %s OK!", fileName);
  661. }
  662. SaveWorldObjectData sd;
  663. sd.m_fileName = fileName;
  664. for (int m =0; m<u2b.getNumModels();m++)
  665. {
  666. u2b.activateModel(m);
  667. btMultiBody* mb = 0;
  668. btRigidBody* rb = 0;
  669. //get a body index
  670. int bodyUniqueId = m_data->allocHandle();
  671. InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
  672. sd.m_bodyUniqueIds.push_back(bodyUniqueId);
  673. u2b.setBodyUniqueId(bodyUniqueId);
  674. {
  675. btScalar mass = 0;
  676. bodyHandle->m_rootLocalInertialFrame.setIdentity();
  677. btVector3 localInertiaDiagonal(0,0,0);
  678. int urdfLinkIndex = u2b.getRootLinkIndex();
  679. u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
  680. }
  681. //todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
  682. int rootLinkIndex = u2b.getRootLinkIndex();
  683. b3Printf("urdf root link index = %d\n",rootLinkIndex);
  684. MyMultiBodyCreator creation(m_data->m_guiHelper);
  685. u2b.getRootTransformInWorld(rootTrans);
  686. ConvertURDF2Bullet(u2b,creation, rootTrans,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),CUF_USE_SDF);
  687. mb = creation.getBulletMultiBody();
  688. rb = creation.getRigidBody();
  689. if (rb)
  690. rb->setUserIndex2(bodyUniqueId);
  691. if (mb)
  692. mb->setUserIndex2(bodyUniqueId);
  693. if (mb)
  694. {
  695. bodyHandle->m_multiBody = mb;
  696. m_data->m_sdfRecentLoadedBodies.push_back(bodyUniqueId);
  697. createJointMotors(mb);
  698. //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
  699. bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
  700. for (int i=0;i<mb->getNumLinks();i++)
  701. {
  702. //disable serialization of the collision objects
  703. int urdfLinkIndex = creation.m_mb2urdfLink[i];
  704. btScalar mass;
  705. btVector3 localInertiaDiagonal(0,0,0);
  706. btTransform localInertialFrame;
  707. u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame);
  708. bodyHandle->m_linkLocalInertialFrames.push_back(localInertialFrame);
  709. std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str());
  710. m_data->m_strings.push_back(linkName);
  711. mb->getLink(i).m_linkName = linkName->c_str();
  712. std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str());
  713. m_data->m_strings.push_back(jointName);
  714. mb->getLink(i).m_jointName = jointName->c_str();
  715. }
  716. std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
  717. m_data->m_strings.push_back(baseName);
  718. mb->setBaseName(baseName->c_str());
  719. } else
  720. {
  721. b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later.");
  722. bodyHandle->m_rigidBody = rb;
  723. }
  724. }
  725. m_data->m_saveWorldBodyData.push_back(sd);
  726. }
  727. return loadOk;
  728. }
  729. bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
  730. bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes)
  731. {
  732. btAssert(m_data->m_dynamicsWorld);
  733. if (!m_data->m_dynamicsWorld)
  734. {
  735. b3Error("loadUrdf: No valid m_dynamicsWorld");
  736. return false;
  737. }
  738. BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
  739. bool loadOk = u2b.loadURDF(fileName, useFixedBase);
  740. if (loadOk)
  741. {
  742. //get a body index
  743. int bodyUniqueId = m_data->allocHandle();
  744. if (bodyUniqueIdPtr)
  745. *bodyUniqueIdPtr= bodyUniqueId;
  746. //quick prototype of 'save world' for crude world editing
  747. {
  748. SaveWorldObjectData sd;
  749. sd.m_fileName = fileName;
  750. sd.m_bodyUniqueIds.push_back(bodyUniqueId);
  751. m_data->m_saveWorldBodyData.push_back(sd);
  752. }
  753. u2b.setBodyUniqueId(bodyUniqueId);
  754. InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
  755. {
  756. btScalar mass = 0;
  757. bodyHandle->m_rootLocalInertialFrame.setIdentity();
  758. btVector3 localInertiaDiagonal(0,0,0);
  759. int urdfLinkIndex = u2b.getRootLinkIndex();
  760. u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
  761. }
  762. if (m_data->m_verboseOutput)
  763. {
  764. b3Printf("loaded %s OK!", fileName);
  765. }
  766. btTransform tr;
  767. tr.setIdentity();
  768. tr.setOrigin(pos);
  769. tr.setRotation(orn);
  770. //int rootLinkIndex = u2b.getRootLinkIndex();
  771. // printf("urdf root link index = %d\n",rootLinkIndex);
  772. MyMultiBodyCreator creation(m_data->m_guiHelper);
  773. ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
  774. for (int i=0;i<u2b.getNumAllocatedCollisionShapes();i++)
  775. {
  776. btCollisionShape* shape =u2b.getAllocatedCollisionShape(i);
  777. m_data->m_collisionShapes.push_back(shape);
  778. }
  779. btMultiBody* mb = creation.getBulletMultiBody();
  780. btRigidBody* rb = creation.getRigidBody();
  781. if (useMultiBody)
  782. {
  783. if (mb)
  784. {
  785. mb->setUserIndex2(bodyUniqueId);
  786. bodyHandle->m_multiBody = mb;
  787. createJointMotors(mb);
  788. //serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire
  789. UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
  790. m_data->m_urdfLinkNameMapper.push_back(util);
  791. util->m_mb = mb;
  792. util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient);
  793. //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
  794. util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0);
  795. bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
  796. for (int i=0;i<mb->getNumLinks();i++)
  797. {
  798. //disable serialization of the collision objects
  799. util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0);
  800. int urdfLinkIndex = creation.m_mb2urdfLink[i];
  801. btScalar mass;
  802. btVector3 localInertiaDiagonal(0,0,0);
  803. btTransform localInertialFrame;
  804. u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame);
  805. bodyHandle->m_linkLocalInertialFrames.push_back(localInertialFrame);
  806. std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str());
  807. m_data->m_strings.push_back(linkName);
  808. util->m_memSerializer->registerNameForPointer(linkName->c_str(),linkName->c_str());
  809. mb->getLink(i).m_linkName = linkName->c_str();
  810. std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str());
  811. m_data->m_strings.push_back(jointName);
  812. util->m_memSerializer->registerNameForPointer(jointName->c_str(),jointName->c_str());
  813. mb->getLink(i).m_jointName = jointName->c_str();
  814. }
  815. std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
  816. m_data->m_strings.push_back(baseName);
  817. util->m_memSerializer->registerNameForPointer(baseName->c_str(),baseName->c_str());
  818. mb->setBaseName(baseName->c_str());
  819. util->m_memSerializer->insertHeader();
  820. int len = mb->calculateSerializeBufferSize();
  821. btChunk* chunk = util->m_memSerializer->allocate(len,1);
  822. const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer);
  823. util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb);
  824. return true;
  825. } else
  826. {
  827. b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later.");
  828. return false;
  829. }
  830. } else
  831. {
  832. if (rb)
  833. {
  834. bodyHandle->m_rigidBody = rb;
  835. rb->setUserIndex2(bodyUniqueId);
  836. return true;
  837. }
  838. }
  839. }
  840. return false;
  841. }
  842. void PhysicsServerCommandProcessor::replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes)
  843. {
  844. if (m_data->m_logPlayback)
  845. {
  846. SharedMemoryCommand clientCmd;
  847. SharedMemoryStatus serverStatus;
  848. bool hasCommand = m_data->m_logPlayback->processNextCommand(&clientCmd);
  849. if (hasCommand)
  850. {
  851. processCommand(clientCmd,serverStatus,bufferServerToClient,bufferSizeInBytes);
  852. }
  853. }
  854. }
  855. int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes)
  856. {
  857. int streamSizeInBytes = 0;
  858. //serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire
  859. InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
  860. btMultiBody* mb = bodyHandle->m_multiBody;
  861. if (mb)
  862. {
  863. UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
  864. m_data->m_urdfLinkNameMapper.push_back(util);
  865. util->m_mb = mb;
  866. util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient);
  867. //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
  868. util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0);
  869. if (mb->getBaseName())
  870. {
  871. util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName());
  872. }
  873. bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
  874. for (int i=0;i<mb->getNumLinks();i++)
  875. {
  876. //disable serialization of the collision objects
  877. util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0);
  878. util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_linkName,mb->getLink(i).m_linkName);
  879. util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_jointName,mb->getLink(i).m_jointName);
  880. }
  881. util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName());
  882. util->m_memSerializer->insertHeader();
  883. int len = mb->calculateSerializeBufferSize();
  884. btChunk* chunk = util->m_memSerializer->allocate(len,1);
  885. const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer);
  886. util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb);
  887. streamSizeInBytes = util->m_memSerializer->getCurrentBufferSize();
  888. }
  889. return streamSizeInBytes;
  890. }
  891. bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
  892. {
  893. bool hasStatus = false;
  894. {
  895. ///we ignore overflow of integer for now
  896. {
  897. //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands
  898. //const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0];
  899. #if 1
  900. if (m_data->m_commandLogger)
  901. {
  902. m_data->m_commandLogger->logCommand(clientCmd);
  903. }
  904. #endif
  905. //m_data->m_testBlock1->m_numProcessedClientCommands++;
  906. //no timestamp yet
  907. int timeStamp = 0;
  908. //catch uninitialized cases
  909. serverStatusOut.m_type = CMD_INVALID_STATUS;
  910. //consume the command
  911. switch (clientCmd.m_type)
  912. {
  913. #if 0
  914. case CMD_SEND_BULLET_DATA_STREAM:
  915. {
  916. if (m_data->m_verboseOutput)
  917. {
  918. b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength);
  919. }
  920. btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
  921. m_data->m_worldImporters.push_back(worldImporter);
  922. bool completedOk = worldImporter->loadFileFromMemory(m_data->m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength);
  923. if (completedOk)
  924. {
  925. SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
  926. m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
  927. m_data->submitServerStatus(status);
  928. } else
  929. {
  930. SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,clientCmd.m_sequenceNumber,timeStamp);
  931. m_data->submitServerStatus(status);
  932. }
  933. break;
  934. }
  935. #endif
  936. case CMD_REQUEST_DEBUG_LINES:
  937. {
  938. int curFlags =m_data->m_remoteDebugDrawer->getDebugMode();
  939. int debugMode = clientCmd.m_requestDebugLinesArguments.m_debugMode;//clientCmd.btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb;
  940. int startingLineIndex = clientCmd.m_requestDebugLinesArguments.m_startingLineIndex;
  941. if (startingLineIndex<0)
  942. {
  943. b3Warning("startingLineIndex should be non-negative");
  944. startingLineIndex = 0;
  945. }
  946. if (clientCmd.m_requestDebugLinesArguments.m_startingLineIndex==0)
  947. {
  948. m_data->m_remoteDebugDrawer->m_lines2.resize(0);
  949. //|btIDebugDraw::DBG_DrawAabb|
  950. // btIDebugDraw::DBG_DrawConstraints |btIDebugDraw::DBG_DrawConstraintLimits ;
  951. m_data->m_remoteDebugDrawer->setDebugMode(debugMode);
  952. btIDebugDraw* oldDebugDrawer = m_data->m_dynamicsWorld->getDebugDrawer();
  953. m_data->m_dynamicsWorld->setDebugDrawer(m_data->m_remoteDebugDrawer);
  954. m_data->m_dynamicsWorld->debugDrawWorld();
  955. m_data->m_dynamicsWorld->setDebugDrawer(oldDebugDrawer);
  956. m_data->m_remoteDebugDrawer->setDebugMode(curFlags);
  957. }
  958. //9 floats per line: 3 floats for 'from', 3 floats for 'to' and 3 floats for 'color'
  959. int maxNumLines = bufferSizeInBytes/(sizeof(float)*9)-1;
  960. if (startingLineIndex >m_data->m_remoteDebugDrawer->m_lines2.size())
  961. {
  962. b3Warning("m_startingLineIndex exceeds total number of debug lines");
  963. startingLineIndex =m_data->m_remoteDebugDrawer->m_lines2.size();
  964. }
  965. int numLines = btMin(maxNumLines,m_data->m_remoteDebugDrawer->m_lines2.size()-startingLineIndex);
  966. if (numLines)
  967. {
  968. float* linesFrom = (float*)bufferServerToClient;
  969. float* linesTo = (float*)(bufferServerToClient+numLines*3*sizeof(float));
  970. float* linesColor = (float*)(bufferServerToClient+2*numLines*3*sizeof(float));
  971. for (int i=0;i<numLines;i++)
  972. {
  973. linesFrom[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.x();
  974. linesTo[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.x();
  975. linesColor[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.x();
  976. linesFrom[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.y();
  977. linesTo[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.y();
  978. linesColor[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.y();
  979. linesFrom[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.z();
  980. linesTo[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.z();
  981. linesColor[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.z();
  982. }
  983. }
  984. serverStatusOut.m_type = CMD_DEBUG_LINES_COMPLETED;
  985. serverStatusOut.m_sendDebugLinesArgs.m_numDebugLines = numLines;
  986. serverStatusOut.m_sendDebugLinesArgs.m_startingLineIndex = startingLineIndex;
  987. serverStatusOut.m_sendDebugLinesArgs.m_numRemainingDebugLines = m_data->m_remoteDebugDrawer->m_lines2.size()-(startingLineIndex+numLines);
  988. hasStatus = true;
  989. break;
  990. }
  991. case CMD_REQUEST_CAMERA_IMAGE_DATA:
  992. {
  993. int startPixelIndex = clientCmd.m_requestPixelDataArguments.m_startPixelIndex;
  994. int width = clientCmd.m_requestPixelDataArguments.m_pixelWidth;
  995. int height = clientCmd.m_requestPixelDataArguments.m_pixelHeight;
  996. int numPixelsCopied = 0;
  997. if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
  998. {
  999. //m_data->m_guiHelper->copyCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,clientCmd.m_requestPixelDataArguments.m_projectionMatrix,0,0,0,0,0,width,height,0);
  1000. }
  1001. else
  1002. {
  1003. if ((clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) &&
  1004. (clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0)
  1005. {
  1006. m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
  1007. clientCmd.m_requestPixelDataArguments.m_pixelHeight);
  1008. }
  1009. m_data->m_visualConverter.getWidthAndHeight(width,height);
  1010. }
  1011. int numTotalPixels = width*height;
  1012. int numRemainingPixels = numTotalPixels - startPixelIndex;
  1013. if (numRemainingPixels>0)
  1014. {
  1015. int totalBytesPerPixel = 4+4+4;//4 for rgb, 4 for depth, 4 for segmentation mask
  1016. int maxNumPixels = bufferSizeInBytes/totalBytesPerPixel-1;
  1017. unsigned char* pixelRGBA = (unsigned char*)bufferServerToClient;
  1018. int numRequestedPixels = btMin(maxNumPixels,numRemainingPixels);
  1019. float* depthBuffer = (float*)(bufferServerToClient+numRequestedPixels*4);
  1020. int* segmentationMaskBuffer = (int*)(bufferServerToClient+numRequestedPixels*8);
  1021. if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
  1022. {
  1023. m_data->m_guiHelper->copyCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,
  1024. clientCmd.m_requestPixelDataArguments.m_projectionMatrix,pixelRGBA,numRequestedPixels,
  1025. depthBuffer,numRequestedPixels,
  1026. segmentationMaskBuffer, numRequestedPixels,
  1027. startPixelIndex,width,height,&numPixelsCopied);
  1028. } else
  1029. {
  1030. if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
  1031. {
  1032. // printf("-------------------------------\nRendering\n");
  1033. if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
  1034. {
  1035. m_data->m_visualConverter.render(
  1036. clientCmd.m_requestPixelDataArguments.m_viewMatrix,
  1037. clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
  1038. } else
  1039. {
  1040. m_data->m_visualConverter.render();
  1041. }
  1042. }
  1043. m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,
  1044. depthBuffer,numRequestedPixels,
  1045. segmentationMaskBuffer, numRequestedPixels,
  1046. startPixelIndex,&width,&height,&numPixelsCopied);
  1047. }
  1048. //each pixel takes 4 RGBA values and 1 float = 8 bytes
  1049. } else
  1050. {
  1051. }
  1052. serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED;
  1053. serverStatusOut.m_sendPixelDataArguments.m_numPixelsCopied = numPixelsCopied;
  1054. serverStatusOut.m_sendPixelDataArguments.m_numRemainingPixels = numRemainingPixels - numPixelsCopied;
  1055. serverStatusOut.m_sendPixelDataArguments.m_startingPixelIndex = startPixelIndex;
  1056. serverStatusOut.m_sendPixelDataArguments.m_imageWidth = width;
  1057. serverStatusOut.m_sendPixelDataArguments.m_imageHeight= height;
  1058. hasStatus = true;
  1059. break;
  1060. }
  1061. case CMD_REQUEST_BODY_INFO:
  1062. {
  1063. const SdfRequestInfoArgs& sdfInfoArgs = clientCmd.m_sdfRequestInfoArgs;
  1064. //stream info into memory
  1065. int streamSizeInBytes = createBodyInfoStream(sdfInfoArgs.m_bodyUniqueId, bufferServerToClient, bufferSizeInBytes);
  1066. serverStatusOut.m_type = CMD_BODY_INFO_COMPLETED;
  1067. serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = sdfInfoArgs.m_bodyUniqueId;
  1068. serverStatusOut.m_dataStreamArguments.m_streamChunkLength = streamSizeInBytes;
  1069. hasStatus = true;
  1070. break;
  1071. }
  1072. case CMD_SAVE_WORLD:
  1073. {
  1074. ///this is a very rudimentary way to save the state of the world, for scene authoring
  1075. ///many todo's, for example save the state of motor controllers etc.
  1076. {
  1077. //saveWorld(clientCmd.m_sdfArguments.m_sdfFileName);
  1078. FILE* f = fopen(clientCmd.m_sdfArguments.m_sdfFileName,"w");
  1079. if (f)
  1080. {
  1081. char line[1024];
  1082. {
  1083. sprintf(line,"import pybullet as p\n");
  1084. int len = strlen(line);
  1085. fwrite(line,len,1,f);
  1086. }
  1087. {
  1088. sprintf(line,"p.connect(p.SHARED_MEMORY)\n");
  1089. int len = strlen(line);
  1090. fwrite(line,len,1,f);
  1091. }
  1092. //for each objects ...
  1093. for (int i=0;i<m_data->m_saveWorldBodyData.size();i++)
  1094. {
  1095. SaveWorldObjectData& sd = m_data->m_saveWorldBodyData[i];
  1096. for (int i=0;i<sd.m_bodyUniqueIds.size();i++)
  1097. {
  1098. {
  1099. int bodyUniqueId = sd.m_bodyUniqueIds[i];
  1100. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  1101. if (body)
  1102. {
  1103. if (body->m_multiBody)
  1104. {
  1105. btMultiBody* mb = body->m_multiBody;
  1106. btTransform comTr = mb->getBaseWorldTransform();
  1107. btTransform tr = comTr * body->m_rootLocalInertialFrame.inverse();
  1108. if (strstr(sd.m_fileName.c_str(),".urdf"))
  1109. {
  1110. sprintf(line,"objects = [p.loadURDF(\"%s\", %f,%f,%f,%f,%f,%f,%f)]\n",sd.m_fileName.c_str(),
  1111. tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2],
  1112. tr.getRotation()[0],tr.getRotation()[1],tr.getRotation()[2],tr.getRotation()[3]);
  1113. int len = strlen(line);
  1114. fwrite(line,len,1,f);
  1115. }
  1116. if (strstr(sd.m_fileName.c_str(),".sdf") && i==0)
  1117. {
  1118. sprintf(line,"objects = p.loadSDF(\"%s\")\n",sd.m_fileName.c_str());
  1119. int len = strlen(line);
  1120. fwrite(line,len,1,f);
  1121. }
  1122. if (strstr(sd.m_fileName.c_str(),".sdf") || ((strstr(sd.m_fileName.c_str(),".urdf")) && mb->getNumLinks()) )
  1123. {
  1124. sprintf(line,"ob = objects[%d]\n",i);
  1125. int len = strlen(line);
  1126. fwrite(line,len,1,f);
  1127. }
  1128. if (strstr(sd.m_fileName.c_str(),".sdf"))
  1129. {
  1130. sprintf(line,"p.resetBasePositionAndOrientation(ob,[%f,%f,%f],[%f,%f,%f,%f])\n",
  1131. comTr.getOrigin()[0],comTr.getOrigin()[1],comTr.getOrigin()[2],
  1132. comTr.getRotation()[0],comTr.getRotation()[1],comTr.getRotation()[2],comTr.getRotation()[3]);
  1133. int len = strlen(line);
  1134. fwrite(line,len,1,f);
  1135. }
  1136. if (mb->getNumLinks())
  1137. {
  1138. {
  1139. sprintf(line,"jointPositions=[");
  1140. int len = strlen(line);
  1141. fwrite(line,len,1,f);
  1142. }
  1143. for (int i=0;i<mb->getNumLinks();i++)
  1144. {
  1145. btScalar jointPos = mb->getJointPosMultiDof(i)[0];
  1146. if (i<mb->getNumLinks()-1)
  1147. {
  1148. sprintf(line," %f,",jointPos);
  1149. int len = strlen(line);
  1150. fwrite(line,len,1,f);
  1151. } else
  1152. {
  1153. sprintf(line," %f ",jointPos);
  1154. int len = strlen(line);
  1155. fwrite(line,len,1,f);
  1156. }
  1157. }
  1158. {
  1159. sprintf(line,"]\nfor jointIndex in range (p.getNumJoints(ob)):\n\tp.resetJointState(ob,jointIndex,jointPositions[jointIndex])\n\n");
  1160. int len = strlen(line);
  1161. fwrite(line,len,1,f);
  1162. }
  1163. }
  1164. } else
  1165. {
  1166. //todo: btRigidBody/btSoftBody etc case
  1167. }
  1168. }
  1169. }
  1170. }
  1171. //for URDF, load at origin, then reposition...
  1172. struct SaveWorldObjectData
  1173. {
  1174. b3AlignedObjectArray<int> m_bodyUniqueIds;
  1175. std::string m_fileName;
  1176. };
  1177. }
  1178. {
  1179. btVector3 grav=this->m_data->m_dynamicsWorld->getGravity();
  1180. sprintf(line,"p.setGravity(%f,%f,%f)\n",grav[0],grav[1],grav[2]);
  1181. int len = strlen(line);
  1182. fwrite(line,len,1,f);
  1183. }
  1184. {
  1185. sprintf(line,"p.stepSimulation()\np.disconnect()\n");
  1186. int len = strlen(line);
  1187. fwrite(line,len,1,f);
  1188. }
  1189. fclose(f);
  1190. }
  1191. serverStatusOut.m_type = CMD_SAVE_WORLD_COMPLETED;
  1192. hasStatus = true;
  1193. break;
  1194. }
  1195. serverStatusOut.m_type = CMD_SAVE_WORLD_FAILED;
  1196. hasStatus = true;
  1197. break;
  1198. }
  1199. case CMD_LOAD_SDF:
  1200. {
  1201. const SdfArgs& sdfArgs = clientCmd.m_sdfArguments;
  1202. if (m_data->m_verboseOutput)
  1203. {
  1204. b3Printf("Processed CMD_LOAD_SDF:%s", sdfArgs.m_sdfFileName);
  1205. }
  1206. bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? sdfArgs.m_useMultiBody : true;
  1207. bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody);
  1208. if (completedOk)
  1209. {
  1210. //serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
  1211. serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size();
  1212. int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies);
  1213. for (int i=0;i<maxBodies;i++)
  1214. {
  1215. serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[i] = m_data->m_sdfRecentLoadedBodies[i];
  1216. }
  1217. serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED;
  1218. } else
  1219. {
  1220. serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
  1221. }
  1222. hasStatus = true;
  1223. break;
  1224. }
  1225. case CMD_LOAD_URDF:
  1226. {
  1227. const UrdfArgs& urdfArgs = clientCmd.m_urdfArguments;
  1228. if (m_data->m_verboseOutput)
  1229. {
  1230. b3Printf("Processed CMD_LOAD_URDF:%s", urdfArgs.m_urdfFileName);
  1231. }
  1232. btAssert((clientCmd.m_updateFlags&URDF_ARGS_FILE_NAME) !=0);
  1233. btAssert(urdfArgs.m_urdfFileName);
  1234. btVector3 initialPos(0,0,0);
  1235. btQuaternion initialOrn(0,0,0,1);
  1236. if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_POSITION)
  1237. {
  1238. initialPos[0] = urdfArgs.m_initialPosition[0];
  1239. initialPos[1] = urdfArgs.m_initialPosition[1];
  1240. initialPos[2] = urdfArgs.m_initialPosition[2];
  1241. }
  1242. if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_ORIENTATION)
  1243. {
  1244. initialOrn[0] = urdfArgs.m_initialOrientation[0];
  1245. initialOrn[1] = urdfArgs.m_initialOrientation[1];
  1246. initialOrn[2] = urdfArgs.m_initialOrientation[2];
  1247. initialOrn[3] = urdfArgs.m_initialOrientation[3];
  1248. }
  1249. bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? urdfArgs.m_useMultiBody : true;
  1250. bool useFixedBase = (clientCmd.m_updateFlags & URDF_ARGS_USE_FIXED_BASE) ? urdfArgs.m_useFixedBase: false;
  1251. int bodyUniqueId;
  1252. //load the actual URDF and send a report: completed or failed
  1253. bool completedOk = loadUrdf(urdfArgs.m_urdfFileName,
  1254. initialPos,initialOrn,
  1255. useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes);
  1256. if (completedOk)
  1257. {
  1258. m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
  1259. serverStatusOut.m_type = CMD_URDF_LOADING_COMPLETED;
  1260. serverStatusOut.m_dataStreamArguments.m_streamChunkLength = 0;
  1261. if (m_data->m_urdfLinkNameMapper.size())
  1262. {
  1263. serverStatusOut.m_dataStreamArguments.m_streamChunkLength = m_data->m_urdfLinkNameMapper.at(m_data->m_urdfLinkNameMapper.size()-1)->m_memSerializer->getCurrentBufferSize();
  1264. }
  1265. serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = bodyUniqueId;
  1266. hasStatus = true;
  1267. } else
  1268. {
  1269. serverStatusOut.m_type = CMD_URDF_LOADING_FAILED;
  1270. hasStatus = true;
  1271. }
  1272. break;
  1273. }
  1274. case CMD_CREATE_SENSOR:
  1275. {
  1276. if (m_data->m_verboseOutput)
  1277. {
  1278. b3Printf("Processed CMD_CREATE_SENSOR");
  1279. }
  1280. int bodyUniqueId = clientCmd.m_createSensorArguments.m_bodyUniqueId;
  1281. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  1282. if (body && body->m_multiBody)
  1283. {
  1284. btMultiBody* mb = body->m_multiBody;
  1285. btAssert(mb);
  1286. for (int i=0;i<clientCmd.m_createSensorArguments.m_numJointSensorChanges;i++)
  1287. {
  1288. int jointIndex = clientCmd.m_createSensorArguments.m_jointIndex[i];
  1289. if (clientCmd.m_createSensorArguments.m_enableJointForceSensor[i])
  1290. {
  1291. if (mb->getLink(jointIndex).m_jointFeedback)
  1292. {
  1293. b3Warning("CMD_CREATE_SENSOR: sensor for joint [%d] already enabled", jointIndex);
  1294. } else
  1295. {
  1296. btMultiBodyJointFeedback* fb = new btMultiBodyJointFeedback();
  1297. fb->m_reactionForces.setZero();
  1298. mb->getLink(jointIndex).m_jointFeedback = fb;
  1299. m_data->m_multiBodyJointFeedbacks.push_back(fb);
  1300. };
  1301. } else
  1302. {
  1303. if (mb->getLink(jointIndex).m_jointFeedback)
  1304. {
  1305. m_data->m_multiBodyJointFeedbacks.remove(mb->getLink(jointIndex).m_jointFeedback);
  1306. delete mb->getLink(jointIndex).m_jointFeedback;
  1307. mb->getLink(jointIndex).m_jointFeedback=0;
  1308. } else
  1309. {
  1310. b3Warning("CMD_CREATE_SENSOR: cannot perform sensor removal request, no sensor on joint [%d]", jointIndex);
  1311. };
  1312. }
  1313. }
  1314. } else
  1315. {
  1316. b3Warning("No btMultiBody in the world. btRigidBody/btTypedConstraint sensor not hooked up yet");
  1317. }
  1318. #if 0
  1319. //todo(erwincoumans) here is some sample code to hook up a force/torque sensor for btTypedConstraint/btRigidBody
  1320. /*
  1321. for (int i=0;i<m_data->m_dynamicsWorld->getNumConstraints();i++)
  1322. {
  1323. btTypedConstraint* c = m_data->m_dynamicsWorld->getConstraint(i);
  1324. btJointFeedback* fb = new btJointFeedback();
  1325. m_data->m_jointFeedbacks.push_back(fb);
  1326. c->setJointFeedback(fb);
  1327. }
  1328. */
  1329. #endif
  1330. serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1331. hasStatus = true;
  1332. break;
  1333. }
  1334. case CMD_SEND_DESIRED_STATE:
  1335. {
  1336. if (m_data->m_verboseOutput)
  1337. {
  1338. b3Printf("Processed CMD_SEND_DESIRED_STATE");
  1339. }
  1340. int bodyUniqueId = clientCmd.m_sendDesiredStateCommandArgument.m_bodyUniqueId;
  1341. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  1342. if (body && body->m_multiBody)
  1343. {
  1344. btMultiBody* mb = body->m_multiBody;
  1345. btAssert(mb);
  1346. switch (clientCmd.m_sendDesiredStateCommandArgument.m_controlMode)
  1347. {
  1348. case CONTROL_MODE_TORQUE:
  1349. {
  1350. if (m_data->m_verboseOutput)
  1351. {
  1352. b3Printf("Using CONTROL_MODE_TORQUE");
  1353. }
  1354. // mb->clearForcesAndTorques();
  1355. int torqueIndex = 6;
  1356. if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
  1357. {
  1358. for (int link=0;link<mb->getNumLinks();link++)
  1359. {
  1360. for (int dof=0;dof<mb->getLink(link).m_dofCount;dof++)
  1361. {
  1362. double torque = 0.f;
  1363. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[torqueIndex]&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
  1364. {
  1365. torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex];
  1366. mb->addJointTorqueMultiDof(link,dof,torque);
  1367. }
  1368. torqueIndex++;
  1369. }
  1370. }
  1371. }
  1372. break;
  1373. }
  1374. case CONTROL_MODE_VELOCITY:
  1375. {
  1376. if (m_data->m_verboseOutput)
  1377. {
  1378. b3Printf("Using CONTROL_MODE_VELOCITY");
  1379. }
  1380. int numMotors = 0;
  1381. //find the joint motors and apply the desired velocity and maximum force/torque
  1382. {
  1383. int dofIndex = 6;//skip the 3 linear + 3 angular degree of freedom entries of the base
  1384. for (int link=0;link<mb->getNumLinks();link++)
  1385. {
  1386. if (supportsJointMotor(mb,link))
  1387. {
  1388. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr;
  1389. if (motor)
  1390. {
  1391. btScalar desiredVelocity = 0.f;
  1392. bool hasDesiredVelocity = false;
  1393. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_QDOT)!=0)
  1394. {
  1395. desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex];
  1396. btScalar kd = 0.1f;
  1397. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] & SIM_DESIRED_STATE_HAS_KD)!=0)
  1398. {
  1399. kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[dofIndex];
  1400. }
  1401. motor->setVelocityTarget(desiredVelocity,kd);
  1402. btScalar kp = 0.f;
  1403. motor->setPositionTarget(0,kp);
  1404. hasDesiredVelocity = true;
  1405. }
  1406. if (hasDesiredVelocity)
  1407. {
  1408. btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime;
  1409. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
  1410. {
  1411. maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime;
  1412. }
  1413. motor->setMaxAppliedImpulse(maxImp);
  1414. }
  1415. numMotors++;
  1416. }
  1417. }
  1418. dofIndex += mb->getLink(link).m_dofCount;
  1419. }
  1420. }
  1421. break;
  1422. }
  1423. case CONTROL_MODE_POSITION_VELOCITY_PD:
  1424. {
  1425. if (m_data->m_verboseOutput)
  1426. {
  1427. b3Printf("Using CONTROL_MODE_POSITION_VELOCITY_PD");
  1428. }
  1429. //compute the force base on PD control
  1430. int numMotors = 0;
  1431. //find the joint motors and apply the desired velocity and maximum force/torque
  1432. {
  1433. int velIndex = 6;//skip the 3 linear + 3 angular degree of freedom velocity entries of the base
  1434. int posIndex = 7;//skip 3 positional and 4 orientation (quaternion) positional degrees of freedom of the base
  1435. for (int link=0;link<mb->getNumLinks();link++)
  1436. {
  1437. if (supportsJointMotor(mb,link))
  1438. {
  1439. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr;
  1440. if (motor)
  1441. {
  1442. bool hasDesiredPosOrVel = false;
  1443. btScalar kp = 0.f;
  1444. btScalar kd = 0.f;
  1445. btScalar desiredVelocity = 0.f;
  1446. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_QDOT)!=0)
  1447. {
  1448. hasDesiredPosOrVel = true;
  1449. desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex];
  1450. kd = 0.1;
  1451. }
  1452. btScalar desiredPosition = 0.f;
  1453. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[posIndex] & SIM_DESIRED_STATE_HAS_Q)!=0)
  1454. {
  1455. hasDesiredPosOrVel = true;
  1456. desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex];
  1457. kp = 0.1;
  1458. }
  1459. if (hasDesiredPosOrVel)
  1460. {
  1461. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KP)!=0)
  1462. {
  1463. kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex];
  1464. }
  1465. if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KD)!=0)
  1466. {
  1467. kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex];
  1468. }
  1469. motor->setVelocityTarget(desiredVelocity,kd);
  1470. motor->setPositionTarget(desiredPosition,kp);
  1471. btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime;
  1472. if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
  1473. maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime;
  1474. motor->setMaxAppliedImpulse(maxImp);
  1475. }
  1476. numMotors++;
  1477. }
  1478. }
  1479. velIndex += mb->getLink(link).m_dofCount;
  1480. posIndex += mb->getLink(link).m_posVarCount;
  1481. }
  1482. }
  1483. break;
  1484. }
  1485. default:
  1486. {
  1487. b3Warning("m_controlMode not implemented yet");
  1488. break;
  1489. }
  1490. }
  1491. }
  1492. serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED;
  1493. hasStatus = true;
  1494. break;
  1495. }
  1496. case CMD_REQUEST_ACTUAL_STATE:
  1497. {
  1498. if (m_data->m_verboseOutput)
  1499. {
  1500. b3Printf("Sending the actual state (Q,U)");
  1501. }
  1502. int bodyUniqueId = clientCmd.m_requestActualStateInformationCommandArgument.m_bodyUniqueId;
  1503. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  1504. if (body && body->m_multiBody)
  1505. {
  1506. btMultiBody* mb = body->m_multiBody;
  1507. SharedMemoryStatus& serverCmd = serverStatusOut;
  1508. serverStatusOut.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
  1509. serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
  1510. int totalDegreeOfFreedomQ = 0;
  1511. int totalDegreeOfFreedomU = 0;
  1512. if (mb->getNumLinks()>= MAX_DEGREE_OF_FREEDOM)
  1513. {
  1514. serverStatusOut.m_type = CMD_ACTUAL_STATE_UPDATE_FAILED;
  1515. hasStatus = true;
  1516. break;
  1517. }
  1518. //always add the base, even for static (non-moving objects)
  1519. //so that we can easily move the 'fixed' base when needed
  1520. //do we don't use this conditional "if (!mb->hasFixedBase())"
  1521. {
  1522. btTransform tr;
  1523. tr.setOrigin(mb->getBasePos());
  1524. tr.setRotation(mb->getWorldToBaseRot().inverse());
  1525. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[0] =
  1526. body->m_rootLocalInertialFrame.getOrigin()[0];
  1527. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[1] =
  1528. body->m_rootLocalInertialFrame.getOrigin()[1];
  1529. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[2] =
  1530. body->m_rootLocalInertialFrame.getOrigin()[2];
  1531. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[3] =
  1532. body->m_rootLocalInertialFrame.getRotation()[0];
  1533. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[4] =
  1534. body->m_rootLocalInertialFrame.getRotation()[1];
  1535. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[5] =
  1536. body->m_rootLocalInertialFrame.getRotation()[2];
  1537. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[6] =
  1538. body->m_rootLocalInertialFrame.getRotation()[3];
  1539. //base position in world space, carthesian
  1540. serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
  1541. serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1];
  1542. serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2];
  1543. //base orientation, quaternion x,y,z,w, in world space, carthesian
  1544. serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0];
  1545. serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1];
  1546. serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2];
  1547. serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3];
  1548. totalDegreeOfFreedomQ +=7;//pos + quaternion
  1549. //base linear velocity (in world space, carthesian)
  1550. serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = mb->getBaseVel()[0];
  1551. serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = mb->getBaseVel()[1];
  1552. serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = mb->getBaseVel()[2];
  1553. //base angular velocity (in world space, carthesian)
  1554. serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = mb->getBaseOmega()[0];
  1555. serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = mb->getBaseOmega()[1];
  1556. serverCmd.m_sendActualStateArgs.m_actualStateQdot[5] = mb->getBaseOmega()[2];
  1557. totalDegreeOfFreedomU += 6;//3 linear and 3 angular DOF
  1558. }
  1559. for (int l=0;l<mb->getNumLinks();l++)
  1560. {
  1561. for (int d=0;d<mb->getLink(l).m_posVarCount;d++)
  1562. {
  1563. serverCmd.m_sendActualStateArgs.m_actualStateQ[totalDegreeOfFreedomQ++] = mb->getJointPosMultiDof(l)[d];
  1564. }
  1565. for (int d=0;d<mb->getLink(l).m_dofCount;d++)
  1566. {
  1567. serverCmd.m_sendActualStateArgs.m_actualStateQdot[totalDegreeOfFreedomU++] = mb->getJointVelMultiDof(l)[d];
  1568. }
  1569. if (0 == mb->getLink(l).m_jointFeedback)
  1570. {
  1571. for (int d=0;d<6;d++)
  1572. {
  1573. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+d]=0;
  1574. }
  1575. } else
  1576. {
  1577. btVector3 sensedForce = mb->getLink(l).m_jointFeedback->m_reactionForces.getLinear();
  1578. btVector3 sensedTorque = mb->getLink(l).m_jointFeedback->m_reactionForces.getAngular();
  1579. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+0] = sensedForce[0];
  1580. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+1] = sensedForce[1];
  1581. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+2] = sensedForce[2];
  1582. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+3] = sensedTorque[0];
  1583. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+4] = sensedTorque[1];
  1584. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+5] = sensedTorque[2];
  1585. }
  1586. serverCmd.m_sendActualStateArgs.m_jointMotorForce[l] = 0;
  1587. if (supportsJointMotor(mb,l))
  1588. {
  1589. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)body->m_multiBody->getLink(l).m_userPtr;
  1590. if (motor && m_data->m_physicsDeltaTime>btScalar(0))
  1591. {
  1592. btScalar force =motor->getAppliedImpulse(0)/m_data->m_physicsDeltaTime;
  1593. serverCmd.m_sendActualStateArgs.m_jointMotorForce[l] =
  1594. force;
  1595. //if (force>0)
  1596. //{
  1597. // b3Printf("force = %f\n", force);
  1598. //}
  1599. }
  1600. }
  1601. btVector3 linkLocalInertialOrigin = body->m_linkLocalInertialFrames[l].getOrigin();
  1602. btQuaternion linkLocalInertialRotation = body->m_linkLocalInertialFrames[l].getRotation();
  1603. btVector3 linkCOMOrigin = mb->getLink(l).m_cachedWorldTransform.getOrigin();
  1604. btQuaternion linkCOMRotation = mb->getLink(l).m_cachedWorldTransform.getRotation();
  1605. serverCmd.m_sendActualStateArgs.m_linkState[l*7+0] = linkCOMOrigin.getX();
  1606. serverCmd.m_sendActualStateArgs.m_linkState[l*7+1] = linkCOMOrigin.getY();
  1607. serverCmd.m_sendActualStateArgs.m_linkState[l*7+2] = linkCOMOrigin.getZ();
  1608. serverCmd.m_sendActualStateArgs.m_linkState[l*7+3] = linkCOMRotation.x();
  1609. serverCmd.m_sendActualStateArgs.m_linkState[l*7+4] = linkCOMRotation.y();
  1610. serverCmd.m_sendActualStateArgs.m_linkState[l*7+5] = linkCOMRotation.z();
  1611. serverCmd.m_sendActualStateArgs.m_linkState[l*7+6] = linkCOMRotation.w();
  1612. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+0] = linkLocalInertialOrigin.getX();
  1613. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+1] = linkLocalInertialOrigin.getY();
  1614. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+2] = linkLocalInertialOrigin.getZ();
  1615. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+3] = linkLocalInertialRotation.x();
  1616. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+4] = linkLocalInertialRotation.y();
  1617. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+5] = linkLocalInertialRotation.z();
  1618. serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+6] = linkLocalInertialRotation.w();
  1619. }
  1620. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ;
  1621. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU;
  1622. hasStatus = true;
  1623. } else
  1624. {
  1625. if (body && body->m_rigidBody)
  1626. {
  1627. btRigidBody* rb = body->m_rigidBody;
  1628. SharedMemoryStatus& serverCmd = serverStatusOut;
  1629. serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
  1630. serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
  1631. int totalDegreeOfFreedomQ = 0;
  1632. int totalDegreeOfFreedomU = 0;
  1633. btTransform tr = rb->getWorldTransform();
  1634. //base position in world space, carthesian
  1635. serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
  1636. serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1];
  1637. serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2];
  1638. //base orientation, quaternion x,y,z,w, in world space, carthesian
  1639. serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0];
  1640. serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1];
  1641. serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2];
  1642. serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3];
  1643. totalDegreeOfFreedomQ +=7;//pos + quaternion
  1644. //base linear velocity (in world space, carthesian)
  1645. serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = rb->getLinearVelocity()[0];
  1646. serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = rb->getLinearVelocity()[1];
  1647. serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = rb->getLinearVelocity()[2];
  1648. //base angular velocity (in world space, carthesian)
  1649. serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = rb->getAngularVelocity()[0];
  1650. serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = rb->getAngularVelocity()[1];
  1651. serverCmd.m_sendActualStateArgs.m_actualStateQdot[5] = rb->getAngularVelocity()[2];
  1652. totalDegreeOfFreedomU += 6;//3 linear and 3 angular DOF
  1653. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ;
  1654. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU;
  1655. hasStatus = true;
  1656. } else
  1657. {
  1658. b3Warning("Request state but no multibody or rigid body available");
  1659. SharedMemoryStatus& serverCmd = serverStatusOut;
  1660. serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_FAILED;
  1661. hasStatus = true;
  1662. }
  1663. }
  1664. break;
  1665. }
  1666. case CMD_STEP_FORWARD_SIMULATION:
  1667. {
  1668. if (m_data->m_verboseOutput)
  1669. {
  1670. b3Printf("Step simulation request");
  1671. b3Printf("CMD_STEP_FORWARD_SIMULATION clientCmd = %d\n", clientCmd.m_sequenceNumber);
  1672. }
  1673. ///todo(erwincoumans) move this damping inside Bullet
  1674. for (int i=0;i<m_data->m_bodyHandles.size();i++)
  1675. {
  1676. applyJointDamping(i);
  1677. }
  1678. btScalar deltaTimeScaled = m_data->m_physicsDeltaTime*simTimeScalingFactor;
  1679. if (m_data->m_numSimulationSubSteps > 0)
  1680. {
  1681. m_data->m_dynamicsWorld->stepSimulation(deltaTimeScaled, m_data->m_numSimulationSubSteps, m_data->m_physicsDeltaTime / m_data->m_numSimulationSubSteps);
  1682. }
  1683. else
  1684. {
  1685. m_data->m_dynamicsWorld->stepSimulation(deltaTimeScaled, 0);
  1686. }
  1687. SharedMemoryStatus& serverCmd =serverStatusOut;
  1688. serverCmd.m_type = CMD_STEP_FORWARD_SIMULATION_COMPLETED;
  1689. hasStatus = true;
  1690. break;
  1691. }
  1692. case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
  1693. {
  1694. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME)
  1695. {
  1696. m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime;
  1697. }
  1698. if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION)
  1699. {
  1700. m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation;
  1701. }
  1702. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY)
  1703. {
  1704. btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0],
  1705. clientCmd.m_physSimParamArgs.m_gravityAcceleration[1],
  1706. clientCmd.m_physSimParamArgs.m_gravityAcceleration[2]);
  1707. this->m_data->m_dynamicsWorld->setGravity(grav);
  1708. if (m_data->m_verboseOutput)
  1709. {
  1710. b3Printf("Updated Gravity: %f,%f,%f",grav[0],grav[1],grav[2]);
  1711. }
  1712. }
  1713. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS)
  1714. {
  1715. m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
  1716. }
  1717. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS)
  1718. {
  1719. m_data->m_numSimulationSubSteps = clientCmd.m_physSimParamArgs.m_numSimulationSubSteps;
  1720. }
  1721. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP)
  1722. {
  1723. m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = clientCmd.m_physSimParamArgs.m_defaultContactERP;
  1724. }
  1725. SharedMemoryStatus& serverCmd =serverStatusOut;
  1726. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1727. hasStatus = true;
  1728. break;
  1729. };
  1730. case CMD_INIT_POSE:
  1731. {
  1732. if (m_data->m_verboseOutput)
  1733. {
  1734. b3Printf("Server Init Pose not implemented yet");
  1735. }
  1736. int bodyUniqueId = clientCmd.m_initPoseArgs.m_bodyUniqueId;
  1737. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  1738. if (body && body->m_multiBody)
  1739. {
  1740. btMultiBody* mb = body->m_multiBody;
  1741. if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION)
  1742. {
  1743. btVector3 zero(0,0,0);
  1744. btAssert(clientCmd.m_initPoseArgs.m_hasInitialStateQ[0] &&
  1745. clientCmd.m_initPoseArgs.m_hasInitialStateQ[1] &&
  1746. clientCmd.m_initPoseArgs.m_hasInitialStateQ[2]);
  1747. mb->setBaseVel(zero);
  1748. mb->setBasePos(btVector3(
  1749. clientCmd.m_initPoseArgs.m_initialStateQ[0],
  1750. clientCmd.m_initPoseArgs.m_initialStateQ[1],
  1751. clientCmd.m_initPoseArgs.m_initialStateQ[2]));
  1752. }
  1753. if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION)
  1754. {
  1755. btAssert(clientCmd.m_initPoseArgs.m_hasInitialStateQ[3] &&
  1756. clientCmd.m_initPoseArgs.m_hasInitialStateQ[4] &&
  1757. clientCmd.m_initPoseArgs.m_hasInitialStateQ[5] &&
  1758. clientCmd.m_initPoseArgs.m_hasInitialStateQ[6]);
  1759. mb->setBaseOmega(btVector3(0,0,0));
  1760. btQuaternion invOrn(clientCmd.m_initPoseArgs.m_initialStateQ[3],
  1761. clientCmd.m_initPoseArgs.m_initialStateQ[4],
  1762. clientCmd.m_initPoseArgs.m_initialStateQ[5],
  1763. clientCmd.m_initPoseArgs.m_initialStateQ[6]);
  1764. mb->setWorldToBaseRot(invOrn.inverse());
  1765. }
  1766. if (clientCmd.m_updateFlags & INIT_POSE_HAS_JOINT_STATE)
  1767. {
  1768. int dofIndex = 7;
  1769. for (int i=0;i<mb->getNumLinks();i++)
  1770. {
  1771. if ( (clientCmd.m_initPoseArgs.m_hasInitialStateQ[dofIndex]) && (mb->getLink(i).m_dofCount==1))
  1772. {
  1773. mb->setJointPos(i,clientCmd.m_initPoseArgs.m_initialStateQ[dofIndex]);
  1774. mb->setJointVel(i,0);
  1775. }
  1776. dofIndex += mb->getLink(i).m_dofCount;
  1777. }
  1778. }
  1779. }
  1780. SharedMemoryStatus& serverCmd =serverStatusOut;
  1781. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1782. hasStatus = true;
  1783. break;
  1784. }
  1785. case CMD_RESET_SIMULATION:
  1786. {
  1787. //clean up all data
  1788. deleteCachedInverseDynamicsBodies();
  1789. if (m_data && m_data->m_guiHelper)
  1790. {
  1791. m_data->m_guiHelper->removeAllGraphicsInstances();
  1792. }
  1793. if (m_data)
  1794. {
  1795. m_data->m_visualConverter.resetAll();
  1796. }
  1797. deleteDynamicsWorld();
  1798. createEmptyDynamicsWorld();
  1799. m_data->exitHandles();
  1800. m_data->initHandles();
  1801. SharedMemoryStatus& serverCmd =serverStatusOut;
  1802. serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED;
  1803. hasStatus = true;
  1804. m_data->m_hasGround = false;
  1805. m_data->m_gripperRigidbodyFixed = 0;
  1806. break;
  1807. }
  1808. case CMD_CREATE_RIGID_BODY:
  1809. case CMD_CREATE_BOX_COLLISION_SHAPE:
  1810. {
  1811. btVector3 halfExtents(1,1,1);
  1812. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_HALF_EXTENTS)
  1813. {
  1814. halfExtents = btVector3(
  1815. clientCmd.m_createBoxShapeArguments.m_halfExtentsX,
  1816. clientCmd.m_createBoxShapeArguments.m_halfExtentsY,
  1817. clientCmd.m_createBoxShapeArguments.m_halfExtentsZ);
  1818. }
  1819. btTransform startTrans;
  1820. startTrans.setIdentity();
  1821. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_POSITION)
  1822. {
  1823. startTrans.setOrigin(btVector3(
  1824. clientCmd.m_createBoxShapeArguments.m_initialPosition[0],
  1825. clientCmd.m_createBoxShapeArguments.m_initialPosition[1],
  1826. clientCmd.m_createBoxShapeArguments.m_initialPosition[2]));
  1827. }
  1828. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_ORIENTATION)
  1829. {
  1830. startTrans.setRotation(btQuaternion(
  1831. clientCmd.m_createBoxShapeArguments.m_initialOrientation[0],
  1832. clientCmd.m_createBoxShapeArguments.m_initialOrientation[1],
  1833. clientCmd.m_createBoxShapeArguments.m_initialOrientation[2],
  1834. clientCmd.m_createBoxShapeArguments.m_initialOrientation[3]));
  1835. }
  1836. btScalar mass = 0.f;
  1837. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_MASS)
  1838. {
  1839. mass = clientCmd.m_createBoxShapeArguments.m_mass;
  1840. }
  1841. int shapeType = COLLISION_SHAPE_TYPE_BOX;
  1842. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE)
  1843. {
  1844. shapeType = clientCmd.m_createBoxShapeArguments.m_collisionShapeType;
  1845. }
  1846. btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
  1847. m_data->m_worldImporters.push_back(worldImporter);
  1848. btCollisionShape* shape = 0;
  1849. switch (shapeType)
  1850. {
  1851. case COLLISION_SHAPE_TYPE_CYLINDER_X:
  1852. {
  1853. btScalar radius = halfExtents[1];
  1854. btScalar height = halfExtents[0];
  1855. shape = worldImporter->createCylinderShapeX(radius,height);
  1856. break;
  1857. }
  1858. case COLLISION_SHAPE_TYPE_CYLINDER_Y:
  1859. {
  1860. btScalar radius = halfExtents[0];
  1861. btScalar height = halfExtents[1];
  1862. shape = worldImporter->createCylinderShapeY(radius,height);
  1863. break;
  1864. }
  1865. case COLLISION_SHAPE_TYPE_CYLINDER_Z:
  1866. {
  1867. btScalar radius = halfExtents[1];
  1868. btScalar height = halfExtents[2];
  1869. shape = worldImporter->createCylinderShapeZ(radius,height);
  1870. break;
  1871. }
  1872. case COLLISION_SHAPE_TYPE_CAPSULE_X:
  1873. {
  1874. btScalar radius = halfExtents[1];
  1875. btScalar height = halfExtents[0];
  1876. shape = worldImporter->createCapsuleShapeX(radius,height);
  1877. break;
  1878. }
  1879. case COLLISION_SHAPE_TYPE_CAPSULE_Y:
  1880. {
  1881. btScalar radius = halfExtents[0];
  1882. btScalar height = halfExtents[1];
  1883. shape = worldImporter->createCapsuleShapeY(radius,height);
  1884. break;
  1885. }
  1886. case COLLISION_SHAPE_TYPE_CAPSULE_Z:
  1887. {
  1888. btScalar radius = halfExtents[1];
  1889. btScalar height = halfExtents[2];
  1890. shape = worldImporter->createCapsuleShapeZ(radius,height);
  1891. break;
  1892. }
  1893. case COLLISION_SHAPE_TYPE_SPHERE:
  1894. {
  1895. btScalar radius = halfExtents[0];
  1896. shape = worldImporter->createSphereShape(radius);
  1897. break;
  1898. }
  1899. case COLLISION_SHAPE_TYPE_BOX:
  1900. default:
  1901. {
  1902. shape = worldImporter->createBoxShape(halfExtents);
  1903. }
  1904. }
  1905. bool isDynamic = (mass>0);
  1906. btRigidBody* rb = worldImporter->createRigidBody(isDynamic,mass,startTrans,shape,0);
  1907. //m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
  1908. btVector4 colorRGBA(1,0,0,1);
  1909. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLOR)
  1910. {
  1911. colorRGBA[0] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[0];
  1912. colorRGBA[1] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[1];
  1913. colorRGBA[2] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[2];
  1914. colorRGBA[3] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[3];
  1915. }
  1916. m_data->m_guiHelper->createCollisionShapeGraphicsObject(rb->getCollisionShape());
  1917. m_data->m_guiHelper->createCollisionObjectGraphicsObject(rb,colorRGBA);
  1918. SharedMemoryStatus& serverCmd =serverStatusOut;
  1919. serverCmd.m_type = CMD_RIGID_BODY_CREATION_COMPLETED;
  1920. int bodyUniqueId = m_data->allocHandle();
  1921. InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
  1922. serverCmd.m_rigidBodyCreateArgs.m_bodyUniqueId = bodyUniqueId;
  1923. rb->setUserIndex2(bodyUniqueId);
  1924. bodyHandle->m_rootLocalInertialFrame.setIdentity();
  1925. bodyHandle->m_rigidBody = rb;
  1926. hasStatus = true;
  1927. break;
  1928. }
  1929. case CMD_PICK_BODY:
  1930. {
  1931. pickBody(btVector3(clientCmd.m_pickBodyArguments.m_rayFromWorld[0],
  1932. clientCmd.m_pickBodyArguments.m_rayFromWorld[1],
  1933. clientCmd.m_pickBodyArguments.m_rayFromWorld[2]),
  1934. btVector3(clientCmd.m_pickBodyArguments.m_rayToWorld[0],
  1935. clientCmd.m_pickBodyArguments.m_rayToWorld[1],
  1936. clientCmd.m_pickBodyArguments.m_rayToWorld[2]));
  1937. SharedMemoryStatus& serverCmd =serverStatusOut;
  1938. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1939. hasStatus = true;
  1940. break;
  1941. }
  1942. case CMD_MOVE_PICKED_BODY:
  1943. {
  1944. movePickedBody(btVector3(clientCmd.m_pickBodyArguments.m_rayFromWorld[0],
  1945. clientCmd.m_pickBodyArguments.m_rayFromWorld[1],
  1946. clientCmd.m_pickBodyArguments.m_rayFromWorld[2]),
  1947. btVector3(clientCmd.m_pickBodyArguments.m_rayToWorld[0],
  1948. clientCmd.m_pickBodyArguments.m_rayToWorld[1],
  1949. clientCmd.m_pickBodyArguments.m_rayToWorld[2]));
  1950. SharedMemoryStatus& serverCmd =serverStatusOut;
  1951. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1952. hasStatus = true;
  1953. break;
  1954. }
  1955. case CMD_REMOVE_PICKING_CONSTRAINT_BODY:
  1956. {
  1957. removePickingConstraint();
  1958. SharedMemoryStatus& serverCmd =serverStatusOut;
  1959. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1960. hasStatus = true;
  1961. break;
  1962. }
  1963. case CMD_REQUEST_CONTACT_POINT_INFORMATION:
  1964. {
  1965. SharedMemoryStatus& serverCmd =serverStatusOut;
  1966. serverCmd.m_sendContactPointArgs.m_numContactPointsCopied = 0;
  1967. //make a snapshot of the contact manifolds into individual contact points
  1968. if (clientCmd.m_requestContactPointArguments.m_startingContactPointIndex==0)
  1969. {
  1970. int numContactManifolds = m_data->m_dynamicsWorld->getDispatcher()->getNumManifolds();
  1971. m_data->m_cachedContactPoints.resize(0);
  1972. m_data->m_cachedContactPoints.reserve(numContactManifolds*4);
  1973. for (int i=0;i<numContactManifolds;i++)
  1974. {
  1975. const btPersistentManifold* manifold = m_data->m_dynamicsWorld->getDispatcher()->getInternalManifoldPointer()[i];
  1976. int linkIndexA = -1;
  1977. int linkIndexB = -1;
  1978. int objectIndexB = -1;
  1979. const btRigidBody* bodyB = btRigidBody::upcast(manifold->getBody1());
  1980. if (bodyB)
  1981. {
  1982. objectIndexB = bodyB->getUserIndex2();
  1983. }
  1984. const btMultiBodyLinkCollider* mblB = btMultiBodyLinkCollider::upcast(manifold->getBody1());
  1985. if (mblB && mblB->m_multiBody)
  1986. {
  1987. linkIndexB = mblB->m_link;
  1988. objectIndexB = mblB->m_multiBody->getUserIndex2();
  1989. }
  1990. int objectIndexA = -1;
  1991. const btRigidBody* bodyA = btRigidBody::upcast(manifold->getBody0());
  1992. if (bodyA)
  1993. {
  1994. objectIndexA = bodyA->getUserIndex2();
  1995. }
  1996. const btMultiBodyLinkCollider* mblA = btMultiBodyLinkCollider::upcast(manifold->getBody0());
  1997. if (mblA && mblA->m_multiBody)
  1998. {
  1999. linkIndexA = mblA->m_link;
  2000. objectIndexA = mblA->m_multiBody->getUserIndex2();
  2001. }
  2002. btAssert(bodyA || mblA);
  2003. //apply the filter, if the user provides it
  2004. if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter>=0)
  2005. {
  2006. if ((clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexA) &&
  2007. (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexB))
  2008. continue;
  2009. }
  2010. //apply the second object filter, if the user provides it
  2011. if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter>=0)
  2012. {
  2013. if ((clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexA) &&
  2014. (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB))
  2015. continue;
  2016. }
  2017. for (int p=0;p<manifold->getNumContacts();p++)
  2018. {
  2019. b3ContactPointData pt;
  2020. pt.m_bodyUniqueIdA = objectIndexA;
  2021. pt.m_bodyUniqueIdB = objectIndexB;
  2022. const btManifoldPoint& srcPt = manifold->getContactPoint(p);
  2023. pt.m_contactDistance = srcPt.getDistance();
  2024. pt.m_contactFlags = 0;
  2025. pt.m_linkIndexA = linkIndexA;
  2026. pt.m_linkIndexB = linkIndexB;
  2027. for (int j=0;j<3;j++)
  2028. {
  2029. pt.m_contactNormalOnBInWS[j] = srcPt.m_normalWorldOnB[j];
  2030. pt.m_positionOnAInWS[j] = srcPt.getPositionWorldOnA()[j];
  2031. pt.m_positionOnBInWS[j] = srcPt.getPositionWorldOnB()[j];
  2032. }
  2033. pt.m_normalForce = srcPt.getAppliedImpulse()/m_data->m_physicsDeltaTime;
  2034. // pt.m_linearFrictionForce = srcPt.m_appliedImpulseLateral1;
  2035. m_data->m_cachedContactPoints.push_back (pt);
  2036. }
  2037. }
  2038. }
  2039. int numContactPoints = m_data->m_cachedContactPoints.size();
  2040. //b3ContactPoint
  2041. //struct b3ContactPointDynamics
  2042. int totalBytesPerContact = sizeof(b3ContactPointData);
  2043. int contactPointStorage = bufferSizeInBytes/totalBytesPerContact-1;
  2044. b3ContactPointData* contactData = (b3ContactPointData*)bufferServerToClient;
  2045. int startContactPointIndex = clientCmd.m_requestContactPointArguments.m_startingContactPointIndex;
  2046. int numContactPointBatch = btMin(numContactPoints,contactPointStorage);
  2047. int endContactPointIndex = startContactPointIndex+numContactPointBatch;
  2048. for (int i=startContactPointIndex;i<endContactPointIndex ;i++)
  2049. {
  2050. const b3ContactPointData& srcPt = m_data->m_cachedContactPoints[i];
  2051. b3ContactPointData& destPt = contactData[serverCmd.m_sendContactPointArgs.m_numContactPointsCopied];
  2052. destPt = srcPt;
  2053. serverCmd.m_sendContactPointArgs.m_numContactPointsCopied++;
  2054. }
  2055. serverCmd.m_sendContactPointArgs.m_startingContactPointIndex = clientCmd.m_requestContactPointArguments.m_startingContactPointIndex;
  2056. serverCmd.m_sendContactPointArgs.m_numRemainingContactPoints = numContactPoints - clientCmd.m_requestContactPointArguments.m_startingContactPointIndex - serverCmd.m_sendContactPointArgs.m_numContactPointsCopied;
  2057. serverCmd.m_type = CMD_CONTACT_POINT_INFORMATION_COMPLETED; //CMD_CONTACT_POINT_INFORMATION_FAILED,
  2058. hasStatus = true;
  2059. break;
  2060. }
  2061. case CMD_CALCULATE_INVERSE_DYNAMICS:
  2062. {
  2063. SharedMemoryStatus& serverCmd = serverStatusOut;
  2064. InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateInverseDynamicsArguments.m_bodyUniqueId);
  2065. if (bodyHandle && bodyHandle->m_multiBody)
  2066. {
  2067. serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_FAILED;
  2068. btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
  2069. if (tree)
  2070. {
  2071. int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
  2072. const int num_dofs = bodyHandle->m_multiBody->getNumDofs();
  2073. btInverseDynamics::vecx nu(num_dofs+baseDofs), qdot(num_dofs + baseDofs), q(num_dofs + baseDofs), joint_force(num_dofs + baseDofs);
  2074. for (int i = 0; i < num_dofs; i++)
  2075. {
  2076. q[i + baseDofs] = clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[i];
  2077. qdot[i + baseDofs] = clientCmd.m_calculateInverseDynamicsArguments.m_jointVelocitiesQdot[i];
  2078. nu[i+baseDofs] = clientCmd.m_calculateInverseDynamicsArguments.m_jointAccelerations[i];
  2079. }
  2080. // Set the gravity to correspond to the world gravity
  2081. btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
  2082. if (-1 != tree->setGravityInWorldFrame(id_grav) &&
  2083. -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
  2084. {
  2085. serverCmd.m_inverseDynamicsResultArgs.m_bodyUniqueId = clientCmd.m_calculateInverseDynamicsArguments.m_bodyUniqueId;
  2086. serverCmd.m_inverseDynamicsResultArgs.m_dofCount = num_dofs;
  2087. for (int i = 0; i < num_dofs; i++)
  2088. {
  2089. serverCmd.m_inverseDynamicsResultArgs.m_jointForces[i] = joint_force[i+baseDofs];
  2090. }
  2091. serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED;
  2092. }
  2093. else
  2094. {
  2095. serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_FAILED;
  2096. }
  2097. }
  2098. }
  2099. else
  2100. {
  2101. serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_FAILED;
  2102. }
  2103. hasStatus = true;
  2104. break;
  2105. }
  2106. case CMD_CALCULATE_JACOBIAN:
  2107. {
  2108. SharedMemoryStatus& serverCmd = serverStatusOut;
  2109. InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateJacobianArguments.m_bodyUniqueId);
  2110. if (bodyHandle && bodyHandle->m_multiBody)
  2111. {
  2112. serverCmd.m_type = CMD_CALCULATED_JACOBIAN_FAILED;
  2113. btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
  2114. if (tree)
  2115. {
  2116. int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
  2117. const int num_dofs = bodyHandle->m_multiBody->getNumDofs();
  2118. btInverseDynamics::vecx nu(num_dofs+baseDofs), qdot(num_dofs + baseDofs), q(num_dofs + baseDofs), joint_force(num_dofs + baseDofs);
  2119. for (int i = 0; i < num_dofs; i++)
  2120. {
  2121. q[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointPositionsQ[i];
  2122. qdot[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointVelocitiesQdot[i];
  2123. nu[i+baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointAccelerations[i];
  2124. }
  2125. // Set the gravity to correspond to the world gravity
  2126. btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
  2127. if (-1 != tree->setGravityInWorldFrame(id_grav) &&
  2128. -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
  2129. {
  2130. serverCmd.m_jacobianResultArgs.m_dofCount = num_dofs;
  2131. // Set jacobian value
  2132. tree->calculateJacobians(q);
  2133. btInverseDynamics::mat3x jac_t(3, num_dofs);
  2134. tree->getBodyJacobianTrans(clientCmd.m_calculateJacobianArguments.m_linkIndex, &jac_t);
  2135. for (int i = 0; i < 3; ++i)
  2136. {
  2137. for (int j = 0; j < num_dofs; ++j)
  2138. {
  2139. serverCmd.m_jacobianResultArgs.m_linearJacobian[i*num_dofs+j] = jac_t(i,j);
  2140. }
  2141. }
  2142. serverCmd.m_type = CMD_CALCULATED_JACOBIAN_COMPLETED;
  2143. }
  2144. else
  2145. {
  2146. serverCmd.m_type = CMD_CALCULATED_JACOBIAN_FAILED;
  2147. }
  2148. }
  2149. }
  2150. else
  2151. {
  2152. serverCmd.m_type = CMD_CALCULATED_JACOBIAN_FAILED;
  2153. }
  2154. hasStatus = true;
  2155. break;
  2156. }
  2157. case CMD_APPLY_EXTERNAL_FORCE:
  2158. {
  2159. if (m_data->m_verboseOutput)
  2160. {
  2161. b3Printf("CMD_APPLY_EXTERNAL_FORCE clientCmd = %d\n", clientCmd.m_sequenceNumber);
  2162. }
  2163. for (int i = 0; i < clientCmd.m_externalForceArguments.m_numForcesAndTorques; ++i)
  2164. {
  2165. InteralBodyData* body = m_data->getHandle(clientCmd.m_externalForceArguments.m_bodyUniqueIds[i]);
  2166. if (body && body->m_multiBody)
  2167. {
  2168. btMultiBody* mb = body->m_multiBody;
  2169. bool isLinkFrame = ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_LINK_FRAME)!=0);
  2170. if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE)!=0)
  2171. {
  2172. btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0],
  2173. clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+1],
  2174. clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+2]);
  2175. btVector3 positionLocal(
  2176. clientCmd.m_externalForceArguments.m_positions[i*3+0],
  2177. clientCmd.m_externalForceArguments.m_positions[i*3+1],
  2178. clientCmd.m_externalForceArguments.m_positions[i*3+2]);
  2179. if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1)
  2180. {
  2181. btVector3 forceWorld = isLinkFrame ? forceLocal : mb->getBaseWorldTransform().getBasis()*forceLocal;
  2182. btVector3 relPosWorld = isLinkFrame ? positionLocal : mb->getBaseWorldTransform().getBasis()*positionLocal;
  2183. mb->addBaseForce(forceWorld);
  2184. mb->addBaseTorque(relPosWorld.cross(forceWorld));
  2185. //b3Printf("apply base force of %f,%f,%f at %f,%f,%f\n", forceWorld[0],forceWorld[1],forceWorld[2],positionLocal[0],positionLocal[1],positionLocal[2]);
  2186. } else
  2187. {
  2188. int link = clientCmd.m_externalForceArguments.m_linkIds[i];
  2189. btVector3 forceWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*forceLocal;
  2190. btVector3 relPosWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*positionLocal;
  2191. mb->addLinkForce(link, forceWorld);
  2192. mb->addLinkTorque(link,relPosWorld.cross(forceWorld));
  2193. //b3Printf("apply link force of %f,%f,%f at %f,%f,%f\n", forceWorld[0],forceWorld[1],forceWorld[2], positionLocal[0],positionLocal[1],positionLocal[2]);
  2194. }
  2195. }
  2196. if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_TORQUE)!=0)
  2197. {
  2198. btVector3 torqueLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0],
  2199. clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+1],
  2200. clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+2]);
  2201. if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1)
  2202. {
  2203. btVector3 torqueWorld = isLinkFrame ? torqueLocal : mb->getBaseWorldTransform().getBasis()*torqueLocal;
  2204. mb->addBaseTorque(torqueWorld);
  2205. //b3Printf("apply base torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]);
  2206. } else
  2207. {
  2208. int link = clientCmd.m_externalForceArguments.m_linkIds[i];
  2209. btVector3 torqueWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*torqueLocal;
  2210. mb->addLinkTorque(link, torqueWorld);
  2211. //b3Printf("apply link torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]);
  2212. }
  2213. }
  2214. }
  2215. }
  2216. SharedMemoryStatus& serverCmd =serverStatusOut;
  2217. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  2218. hasStatus = true;
  2219. break;
  2220. }
  2221. case CMD_CREATE_JOINT:
  2222. {
  2223. InteralBodyData* parentBody = m_data->getHandle(clientCmd.m_createJointArguments.m_parentBodyIndex);
  2224. if (parentBody && parentBody->m_multiBody)
  2225. {
  2226. InteralBodyData* childBody = m_data->getHandle(clientCmd.m_createJointArguments.m_childBodyIndex);
  2227. if (childBody)
  2228. {
  2229. btVector3 pivotInParent(clientCmd.m_createJointArguments.m_parentFrame[0], clientCmd.m_createJointArguments.m_parentFrame[1], clientCmd.m_createJointArguments.m_parentFrame[2]);
  2230. btVector3 pivotInChild(clientCmd.m_createJointArguments.m_childFrame[0], clientCmd.m_createJointArguments.m_childFrame[1], clientCmd.m_createJointArguments.m_childFrame[2]);
  2231. btMatrix3x3 frameInParent(btQuaternion(clientCmd.m_createJointArguments.m_parentFrame[3], clientCmd.m_createJointArguments.m_parentFrame[4], clientCmd.m_createJointArguments.m_parentFrame[5], clientCmd.m_createJointArguments.m_parentFrame[6]));
  2232. btMatrix3x3 frameInChild(btQuaternion(clientCmd.m_createJointArguments.m_childFrame[3], clientCmd.m_createJointArguments.m_childFrame[4], clientCmd.m_createJointArguments.m_childFrame[5], clientCmd.m_createJointArguments.m_childFrame[6]));
  2233. btVector3 jointAxis(clientCmd.m_createJointArguments.m_jointAxis[0], clientCmd.m_createJointArguments.m_jointAxis[1], clientCmd.m_createJointArguments.m_jointAxis[2]);
  2234. if (clientCmd.m_createJointArguments.m_jointType == eFixedType)
  2235. {
  2236. if (childBody->m_multiBody)
  2237. {
  2238. btMultiBodyFixedConstraint* multibodyFixed = new btMultiBodyFixedConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_multiBody,clientCmd.m_createJointArguments.m_childJointIndex,pivotInParent,pivotInChild,frameInParent,frameInChild);
  2239. multibodyFixed->setMaxAppliedImpulse(500.0);
  2240. m_data->m_dynamicsWorld->addMultiBodyConstraint(multibodyFixed);
  2241. }
  2242. else
  2243. {
  2244. btMultiBodyFixedConstraint* rigidbodyFixed = new btMultiBodyFixedConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_rigidBody,pivotInParent,pivotInChild,frameInParent,frameInChild);
  2245. rigidbodyFixed->setMaxAppliedImpulse(500.0);
  2246. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  2247. world->addMultiBodyConstraint(rigidbodyFixed);
  2248. }
  2249. }
  2250. else if (clientCmd.m_createJointArguments.m_jointType == ePrismaticType)
  2251. {
  2252. if (childBody->m_multiBody)
  2253. {
  2254. btMultiBodySliderConstraint* multibodySlider = new btMultiBodySliderConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_multiBody,clientCmd.m_createJointArguments.m_childJointIndex,pivotInParent,pivotInChild,frameInParent,frameInChild,jointAxis);
  2255. multibodySlider->setMaxAppliedImpulse(500.0);
  2256. m_data->m_dynamicsWorld->addMultiBodyConstraint(multibodySlider);
  2257. }
  2258. else
  2259. {
  2260. btMultiBodySliderConstraint* rigidbodySlider = new btMultiBodySliderConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_rigidBody,pivotInParent,pivotInChild,frameInParent,frameInChild,jointAxis);
  2261. rigidbodySlider->setMaxAppliedImpulse(500.0);
  2262. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  2263. world->addMultiBodyConstraint(rigidbodySlider);
  2264. }
  2265. } else if (clientCmd.m_createJointArguments.m_jointType == ePoint2PointType)
  2266. {
  2267. if (childBody->m_multiBody)
  2268. {
  2269. btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_multiBody,clientCmd.m_createJointArguments.m_childJointIndex,pivotInParent,pivotInChild);
  2270. p2p->setMaxAppliedImpulse(500);
  2271. m_data->m_dynamicsWorld->addMultiBodyConstraint(p2p);
  2272. }
  2273. else
  2274. {
  2275. btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_rigidBody,pivotInParent,pivotInChild);
  2276. p2p->setMaxAppliedImpulse(500);
  2277. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  2278. world->addMultiBodyConstraint(p2p);
  2279. }
  2280. }
  2281. }
  2282. }
  2283. SharedMemoryStatus& serverCmd =serverStatusOut;
  2284. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  2285. hasStatus = true;
  2286. break;
  2287. }
  2288. case CMD_CALCULATE_INVERSE_KINEMATICS:
  2289. {
  2290. SharedMemoryStatus& serverCmd = serverStatusOut;
  2291. serverCmd.m_type = CMD_CALCULATE_INVERSE_KINEMATICS_FAILED;
  2292. InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateInverseKinematicsArguments.m_bodyUniqueId);
  2293. if (bodyHandle && bodyHandle->m_multiBody)
  2294. {
  2295. IKTrajectoryHelper** ikHelperPtrPtr = m_data->m_inverseKinematicsHelpers.find(bodyHandle->m_multiBody);
  2296. IKTrajectoryHelper* ikHelperPtr = 0;
  2297. if (ikHelperPtrPtr)
  2298. {
  2299. ikHelperPtr = *ikHelperPtrPtr;
  2300. }
  2301. else
  2302. {
  2303. IKTrajectoryHelper* tmpHelper = new IKTrajectoryHelper;
  2304. m_data->m_inverseKinematicsHelpers.insert(bodyHandle->m_multiBody, tmpHelper);
  2305. ikHelperPtr = tmpHelper;
  2306. }
  2307. int endEffectorLinkIndex = clientCmd.m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex;
  2308. if (ikHelperPtr && (endEffectorLinkIndex<bodyHandle->m_multiBody->getNumLinks()))
  2309. {
  2310. const int numDofs = bodyHandle->m_multiBody->getNumDofs();
  2311. b3AlignedObjectArray<double> jacobian_linear;
  2312. jacobian_linear.resize(3*numDofs);
  2313. b3AlignedObjectArray<double> jacobian_angular;
  2314. jacobian_angular.resize(3*numDofs);
  2315. int jacSize = 0;
  2316. btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
  2317. btAlignedObjectArray<double> q_current;
  2318. q_current.resize(numDofs);
  2319. if (tree)
  2320. {
  2321. jacSize = jacobian_linear.size();
  2322. // Set jacobian value
  2323. int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
  2324. btInverseDynamics::vecx nu(numDofs+baseDofs), qdot(numDofs + baseDofs), q(numDofs + baseDofs), joint_force(numDofs + baseDofs);
  2325. for (int i = 0; i < numDofs; i++)
  2326. {
  2327. q_current[i] = bodyHandle->m_multiBody->getJointPos(i);
  2328. q[i+baseDofs] = bodyHandle->m_multiBody->getJointPos(i);
  2329. qdot[i + baseDofs] = 0;
  2330. nu[i+baseDofs] = 0;
  2331. }
  2332. // Set the gravity to correspond to the world gravity
  2333. btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
  2334. if (-1 != tree->setGravityInWorldFrame(id_grav) &&
  2335. -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
  2336. {
  2337. tree->calculateJacobians(q);
  2338. btInverseDynamics::mat3x jac_t(3, numDofs);
  2339. btInverseDynamics::mat3x jac_r(3,numDofs);
  2340. tree->getBodyJacobianTrans(endEffectorLinkIndex, &jac_t);
  2341. tree->getBodyJacobianRot(endEffectorLinkIndex, &jac_r);
  2342. for (int i = 0; i < 3; ++i)
  2343. {
  2344. for (int j = 0; j < numDofs; ++j)
  2345. {
  2346. jacobian_linear[i*numDofs+j] = jac_t(i,j);
  2347. jacobian_angular[i*numDofs+j] = jac_r(i,j);
  2348. }
  2349. }
  2350. }
  2351. }
  2352. btAlignedObjectArray<double> q_new;
  2353. q_new.resize(numDofs);
  2354. int ikMethod = 0;
  2355. if ((clientCmd.m_updateFlags& IK_HAS_TARGET_ORIENTATION)&&(clientCmd.m_updateFlags&IK_HAS_NULL_SPACE_VELOCITY))
  2356. {
  2357. ikMethod = IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE;
  2358. }
  2359. else if (clientCmd.m_updateFlags& IK_HAS_TARGET_ORIENTATION)
  2360. {
  2361. ikMethod = IK2_VEL_DLS_WITH_ORIENTATION;
  2362. }
  2363. else if (clientCmd.m_updateFlags& IK_HAS_NULL_SPACE_VELOCITY)
  2364. {
  2365. ikMethod = IK2_VEL_DLS_WITH_NULLSPACE;
  2366. }
  2367. else
  2368. {
  2369. ikMethod = IK2_VEL_DLS;
  2370. }
  2371. if (clientCmd.m_updateFlags& IK_HAS_NULL_SPACE_VELOCITY)
  2372. {
  2373. btAlignedObjectArray<double> lower_limit;
  2374. btAlignedObjectArray<double> upper_limit;
  2375. btAlignedObjectArray<double> joint_range;
  2376. btAlignedObjectArray<double> rest_pose;
  2377. lower_limit.resize(numDofs);
  2378. upper_limit.resize(numDofs);
  2379. joint_range.resize(numDofs);
  2380. rest_pose.resize(numDofs);
  2381. for (int i = 0; i < numDofs; ++i)
  2382. {
  2383. lower_limit[i] = clientCmd.m_calculateInverseKinematicsArguments.m_lowerLimit[i];
  2384. upper_limit[i] = clientCmd.m_calculateInverseKinematicsArguments.m_upperLimit[i];
  2385. joint_range[i] = clientCmd.m_calculateInverseKinematicsArguments.m_jointRange[i];
  2386. rest_pose[i] = clientCmd.m_calculateInverseKinematicsArguments.m_restPose[i];
  2387. }
  2388. ikHelperPtr->computeNullspaceVel(numDofs, &q_current[0], &lower_limit[0], &upper_limit[0], &joint_range[0], &rest_pose[0]);
  2389. }
  2390. btTransform endEffectorTransformWorld = bodyHandle->m_multiBody->getLink(endEffectorLinkIndex).m_cachedWorldTransform * bodyHandle->m_linkLocalInertialFrames[endEffectorLinkIndex].inverse();
  2391. btVector3DoubleData endEffectorWorldPosition;
  2392. btVector3DoubleData endEffectorWorldOrientation;
  2393. btVector3 endEffectorPosWorld = endEffectorTransformWorld.getOrigin();
  2394. btQuaternion endEffectorOriWorld = endEffectorTransformWorld.getRotation();
  2395. btVector4 endEffectorOri(endEffectorOriWorld.x(),endEffectorOriWorld.y(),endEffectorOriWorld.z(),endEffectorOriWorld.w());
  2396. endEffectorPosWorld.serializeDouble(endEffectorWorldPosition);
  2397. endEffectorOri.serializeDouble(endEffectorWorldOrientation);
  2398. double dampIK[6] = { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 };
  2399. ikHelperPtr->computeIK(clientCmd.m_calculateInverseKinematicsArguments.m_targetPosition, clientCmd.m_calculateInverseKinematicsArguments.m_targetOrientation,
  2400. endEffectorWorldPosition.m_floats, endEffectorWorldOrientation.m_floats,
  2401. &q_current[0],
  2402. numDofs, clientCmd.m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex,
  2403. &q_new[0], ikMethod, &jacobian_linear[0], &jacobian_angular[0], jacSize*2, dampIK);
  2404. serverCmd.m_inverseKinematicsResultArgs.m_bodyUniqueId =clientCmd.m_calculateInverseDynamicsArguments.m_bodyUniqueId;
  2405. for (int i=0;i<numDofs;i++)
  2406. {
  2407. serverCmd.m_inverseKinematicsResultArgs.m_jointPositions[i] = q_new[i];
  2408. }
  2409. serverCmd.m_inverseKinematicsResultArgs.m_dofCount = numDofs;
  2410. serverCmd.m_type = CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED;
  2411. }
  2412. }
  2413. hasStatus = true;
  2414. break;
  2415. }
  2416. default:
  2417. {
  2418. b3Error("Unknown command encountered");
  2419. SharedMemoryStatus& serverCmd =serverStatusOut;
  2420. serverCmd.m_type = CMD_UNKNOWN_COMMAND_FLUSHED;
  2421. hasStatus = true;
  2422. }
  2423. };
  2424. }
  2425. }
  2426. return hasStatus;
  2427. }
  2428. static int skip=1;
  2429. void PhysicsServerCommandProcessor::renderScene()
  2430. {
  2431. if (m_data->m_guiHelper)
  2432. {
  2433. m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld);
  2434. m_data->m_guiHelper->render(m_data->m_dynamicsWorld);
  2435. }
  2436. }
  2437. void PhysicsServerCommandProcessor::physicsDebugDraw(int debugDrawFlags)
  2438. {
  2439. if (m_data->m_dynamicsWorld)
  2440. {
  2441. if (m_data->m_dynamicsWorld->getDebugDrawer())
  2442. {
  2443. m_data->m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugDrawFlags);
  2444. m_data->m_dynamicsWorld->debugDrawWorld();
  2445. }
  2446. }
  2447. }
  2448. bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
  2449. {
  2450. if (m_data->m_dynamicsWorld==0)
  2451. return false;
  2452. btCollisionWorld::ClosestRayResultCallback rayCallback(rayFromWorld, rayToWorld);
  2453. m_data->m_dynamicsWorld->rayTest(rayFromWorld, rayToWorld, rayCallback);
  2454. if (rayCallback.hasHit())
  2455. {
  2456. btVector3 pickPos = rayCallback.m_hitPointWorld;
  2457. gLastPickPos = pickPos;
  2458. btRigidBody* body = (btRigidBody*)btRigidBody::upcast(rayCallback.m_collisionObject);
  2459. if (body)
  2460. {
  2461. //other exclusions?
  2462. if (!(body->isStaticObject() || body->isKinematicObject()))
  2463. {
  2464. m_data->m_pickedBody = body;
  2465. m_data->m_pickedBody->setActivationState(DISABLE_DEACTIVATION);
  2466. //printf("pickPos=%f,%f,%f\n",pickPos.getX(),pickPos.getY(),pickPos.getZ());
  2467. btVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos;
  2468. btPoint2PointConstraint* p2p = new btPoint2PointConstraint(*body, localPivot);
  2469. m_data->m_dynamicsWorld->addConstraint(p2p, true);
  2470. m_data->m_pickedConstraint = p2p;
  2471. btScalar mousePickClamping = 30.f;
  2472. p2p->m_setting.m_impulseClamp = mousePickClamping;
  2473. //very weak constraint for picking
  2474. p2p->m_setting.m_tau = 0.001f;
  2475. }
  2476. } else
  2477. {
  2478. btMultiBodyLinkCollider* multiCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(rayCallback.m_collisionObject);
  2479. if (multiCol && multiCol->m_multiBody)
  2480. {
  2481. m_data->m_prevCanSleep = multiCol->m_multiBody->getCanSleep();
  2482. multiCol->m_multiBody->setCanSleep(false);
  2483. btVector3 pivotInA = multiCol->m_multiBody->worldPosToLocal(multiCol->m_link, pickPos);
  2484. btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(multiCol->m_multiBody,multiCol->m_link,0,pivotInA,pickPos);
  2485. //if you add too much energy to the system, causing high angular velocities, simulation 'explodes'
  2486. //see also http://www.bulletphysics.org/Bullet/phpBB3/viewtopic.php?f=4&t=949
  2487. //so we try to avoid it by clamping the maximum impulse (force) that the mouse pick can apply
  2488. //it is not satisfying, hopefully we find a better solution (higher order integrator, using joint friction using a zero-velocity target motor with limited force etc?)
  2489. btScalar scaling=1;
  2490. p2p->setMaxAppliedImpulse(2*scaling);
  2491. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  2492. world->addMultiBodyConstraint(p2p);
  2493. m_data->m_pickingMultiBodyPoint2Point =p2p;
  2494. }
  2495. }
  2496. // pickObject(pickPos, rayCallback.m_collisionObject);
  2497. m_data->m_oldPickingPos = rayToWorld;
  2498. m_data->m_hitPos = pickPos;
  2499. m_data->m_oldPickingDist = (pickPos - rayFromWorld).length();
  2500. // printf("hit !\n");
  2501. //add p2p
  2502. }
  2503. return false;
  2504. }
  2505. bool PhysicsServerCommandProcessor::movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
  2506. {
  2507. if (m_data->m_pickedBody && m_data->m_pickedConstraint)
  2508. {
  2509. btPoint2PointConstraint* pickCon = static_cast<btPoint2PointConstraint*>(m_data->m_pickedConstraint);
  2510. if (pickCon)
  2511. {
  2512. //keep it at the same picking distance
  2513. btVector3 dir = rayToWorld-rayFromWorld;
  2514. dir.normalize();
  2515. dir *= m_data->m_oldPickingDist;
  2516. btVector3 newPivotB = rayFromWorld + dir;
  2517. pickCon->setPivotB(newPivotB);
  2518. }
  2519. }
  2520. if (m_data->m_pickingMultiBodyPoint2Point)
  2521. {
  2522. //keep it at the same picking distance
  2523. btVector3 dir = rayToWorld-rayFromWorld;
  2524. dir.normalize();
  2525. dir *= m_data->m_oldPickingDist;
  2526. btVector3 newPivotB = rayFromWorld + dir;
  2527. m_data->m_pickingMultiBodyPoint2Point->setPivotInB(newPivotB);
  2528. }
  2529. return false;
  2530. }
  2531. void PhysicsServerCommandProcessor::removePickingConstraint()
  2532. {
  2533. if (m_data->m_pickedConstraint)
  2534. {
  2535. m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint);
  2536. delete m_data->m_pickedConstraint;
  2537. m_data->m_pickedConstraint = 0;
  2538. m_data->m_pickedBody->forceActivationState(ACTIVE_TAG);
  2539. m_data->m_pickedBody = 0;
  2540. }
  2541. if (m_data->m_pickingMultiBodyPoint2Point)
  2542. {
  2543. m_data->m_pickingMultiBodyPoint2Point->getMultiBodyA()->setCanSleep(m_data->m_prevCanSleep);
  2544. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  2545. world->removeMultiBodyConstraint(m_data->m_pickingMultiBodyPoint2Point);
  2546. delete m_data->m_pickingMultiBodyPoint2Point;
  2547. m_data->m_pickingMultiBodyPoint2Point = 0;
  2548. }
  2549. }
  2550. void PhysicsServerCommandProcessor::enableCommandLogging(bool enable, const char* fileName)
  2551. {
  2552. if (enable)
  2553. {
  2554. if (0==m_data->m_commandLogger)
  2555. {
  2556. m_data->m_commandLogger = new CommandLogger(fileName);
  2557. }
  2558. } else
  2559. {
  2560. if (0!=m_data->m_commandLogger)
  2561. {
  2562. delete m_data->m_commandLogger;
  2563. m_data->m_commandLogger = 0;
  2564. }
  2565. }
  2566. }
  2567. void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
  2568. {
  2569. CommandLogPlayback* pb = new CommandLogPlayback(fileName);
  2570. m_data->m_logPlayback = pb;
  2571. }
  2572. btVector3 gVRGripperPos(0,0,0.2);
  2573. btQuaternion gVRGripperOrn(0,0,0,1);
  2574. btVector3 gVRController2Pos(0,0,0.2);
  2575. btQuaternion gVRController2Orn(0,0,0,1);
  2576. btScalar gVRGripper2Analog = 0;
  2577. btScalar gVRGripperAnalog = 0;
  2578. bool gVRGripperClosed = false;
  2579. int gDroppedSimulationSteps = 0;
  2580. int gNumSteps = 0;
  2581. double gDtInSec = 0.f;
  2582. double gSubStep = 0.f;
  2583. void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
  2584. {
  2585. if ((gEnableRealTimeSimVR || m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
  2586. {
  2587. static btAlignedObjectArray<char> gBufferServerToClient;
  2588. gBufferServerToClient.resize(SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
  2589. int bodyId = 0;
  2590. if (gCreateObjectSimVR >= 0)
  2591. {
  2592. gCreateObjectSimVR = -1;
  2593. btMatrix3x3 mat(gVRGripperOrn);
  2594. btScalar spawnDistance = 0.1;
  2595. btVector3 spawnDir = mat.getColumn(0);
  2596. btVector3 shiftPos = spawnDir*spawnDistance;
  2597. btVector3 spawnPos = gVRGripperPos + shiftPos;
  2598. loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2599. //loadUrdf("lego/lego.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2600. m_data->m_sphereId = bodyId;
  2601. InteralBodyData* parentBody = m_data->getHandle(bodyId);
  2602. if (parentBody->m_multiBody)
  2603. {
  2604. parentBody->m_multiBody->setBaseVel(spawnDir * 5);
  2605. }
  2606. }
  2607. ///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
  2608. if (gCreateSamuraiRobotAssets)
  2609. {
  2610. if (!m_data->m_hasGround)
  2611. {
  2612. m_data->m_hasGround = true;
  2613. loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2614. loadUrdf("samurai.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2615. if (m_data->m_gripperRigidbodyFixed == 0)
  2616. {
  2617. int bodyId = 0;
  2618. if (loadUrdf("pr2_gripper.urdf", btVector3(0, 0, 0.1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()))
  2619. {
  2620. InteralBodyData* parentBody = m_data->getHandle(bodyId);
  2621. if (parentBody->m_multiBody)
  2622. {
  2623. parentBody->m_multiBody->setHasSelfCollision(0);
  2624. btVector3 pivotInParent(0.2, 0, 0);
  2625. btMatrix3x3 frameInParent;
  2626. //frameInParent.setRotation(btQuaternion(0, 0, 0, 1));
  2627. frameInParent.setIdentity();
  2628. btVector3 pivotInChild(0, 0, 0);
  2629. btMatrix3x3 frameInChild;
  2630. frameInChild.setIdentity();
  2631. m_data->m_gripperRigidbodyFixed = new btMultiBodyFixedConstraint(parentBody->m_multiBody, -1, 0, pivotInParent, pivotInChild, frameInParent, frameInChild);
  2632. m_data->m_gripperMultiBody = parentBody->m_multiBody;
  2633. if (m_data->m_gripperMultiBody->getNumLinks() > 2)
  2634. {
  2635. m_data->m_gripperMultiBody->setJointPos(0, 0);
  2636. m_data->m_gripperMultiBody->setJointPos(2, 0);
  2637. }
  2638. m_data->m_gripperRigidbodyFixed->setMaxAppliedImpulse(500);
  2639. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*)m_data->m_dynamicsWorld;
  2640. world->addMultiBodyConstraint(m_data->m_gripperRigidbodyFixed);
  2641. }
  2642. }
  2643. }
  2644. loadUrdf("kuka_iiwa/model_vr_limits.urdf", btVector3(1.4, -0.2, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2645. m_data->m_KukaId = bodyId;
  2646. loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .7), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2647. loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .8), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2648. loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .9), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2649. loadUrdf("r2d2.urdf", btVector3(-2, -4, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2650. // Load one motor gripper for kuka
  2651. loadSdf("gripper/wsg50_one_motor_gripper_new_free_base.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
  2652. m_data->m_gripperId = bodyId + 1;
  2653. InteralBodyData* kukaBody = m_data->getHandle(m_data->m_KukaId);
  2654. InteralBodyData* gripperBody = m_data->getHandle(m_data->m_gripperId);
  2655. // Reset the default gripper motor maximum torque for damping to 0
  2656. for (int i = 0; i < gripperBody->m_multiBody->getNumLinks(); i++)
  2657. {
  2658. if (supportsJointMotor(gripperBody->m_multiBody, i))
  2659. {
  2660. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)gripperBody->m_multiBody->getLink(i).m_userPtr;
  2661. if (motor)
  2662. {
  2663. motor->setMaxAppliedImpulse(0);
  2664. }
  2665. }
  2666. }
  2667. for (int i = 0; i < 6; i++)
  2668. {
  2669. loadUrdf("jenga/jenga.urdf", btVector3(1.3-0.1*i,-0.7, .75), btQuaternion(btVector3(0,1,0),SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2670. }
  2671. //loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2672. // Add slider joint for fingers
  2673. btVector3 pivotInParent1(-0.055, 0, 0.02);
  2674. btVector3 pivotInChild1(0, 0, 0);
  2675. btMatrix3x3 frameInParent1(btQuaternion(0, 0, 0, 1.0));
  2676. btMatrix3x3 frameInChild1(btQuaternion(0, 0, 0, 1.0));
  2677. btVector3 jointAxis1(1.0, 0, 0);
  2678. btVector3 pivotInParent2(0.055, 0, 0.02);
  2679. btVector3 pivotInChild2(0, 0, 0);
  2680. btMatrix3x3 frameInParent2(btQuaternion(0, 0, 0, 1.0));
  2681. btMatrix3x3 frameInChild2(btQuaternion(0, 0, 1.0, 0));
  2682. btVector3 jointAxis2(1.0, 0, 0);
  2683. m_data->m_kukaGripperRevolute1 = new btMultiBodyPoint2Point(gripperBody->m_multiBody, 2, gripperBody->m_multiBody, 4, pivotInParent1, pivotInChild1);
  2684. m_data->m_kukaGripperRevolute1->setMaxAppliedImpulse(5.0);
  2685. m_data->m_kukaGripperRevolute2 = new btMultiBodyPoint2Point(gripperBody->m_multiBody, 3, gripperBody->m_multiBody, 6, pivotInParent2, pivotInChild2);
  2686. m_data->m_kukaGripperRevolute2->setMaxAppliedImpulse(5.0);
  2687. m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperRevolute1);
  2688. m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperRevolute2);
  2689. if (kukaBody->m_multiBody && kukaBody->m_multiBody->getNumDofs()==7)
  2690. {
  2691. gripperBody->m_multiBody->setHasSelfCollision(0);
  2692. btVector3 pivotInParent(0, 0, 0.05);
  2693. btMatrix3x3 frameInParent;
  2694. frameInParent.setIdentity();
  2695. btVector3 pivotInChild(0, 0, 0);
  2696. btMatrix3x3 frameInChild;
  2697. frameInChild.setIdentity();
  2698. m_data->m_kukaGripperFixed = new btMultiBodyFixedConstraint(kukaBody->m_multiBody, 6, gripperBody->m_multiBody, 0, pivotInParent, pivotInChild, frameInParent, frameInChild);
  2699. m_data->m_kukaGripperMultiBody = gripperBody->m_multiBody;
  2700. m_data->m_kukaGripperFixed->setMaxAppliedImpulse(500);
  2701. m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperFixed);
  2702. }
  2703. for (int i = 0; i < 10; i++)
  2704. {
  2705. loadUrdf("cube.urdf", btVector3(-4, -2, 0.5 + i), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2706. }
  2707. loadUrdf("sphere2.urdf", btVector3(-5, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2708. loadUrdf("sphere2.urdf", btVector3(-5, 0, 2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2709. loadUrdf("sphere2.urdf", btVector3(-5, 0, 3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2710. btTransform objectLocalTr[] = {
  2711. btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.0, 0.0, 0.0)),
  2712. btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.0, 0.15, 0.64)),
  2713. btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.1, 0.15, 0.85)),
  2714. btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.4, 0.05, 0.85)),
  2715. btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.3, -0.05, 0.7)),
  2716. btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.1, 0.05, 0.7)),
  2717. btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.2, 0.15, 0.7)),
  2718. btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.2, 0.15, 0.9)),
  2719. btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.2, 0.05, 0.8))
  2720. };
  2721. btAlignedObjectArray<btTransform> objectWorldTr;
  2722. int numOb = sizeof(objectLocalTr) / sizeof(btTransform);
  2723. objectWorldTr.resize(numOb);
  2724. btTransform tr;
  2725. tr.setIdentity();
  2726. tr.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI));
  2727. tr.setOrigin(btVector3(1.0, -0.2, 0));
  2728. for (int i = 0; i < numOb; i++)
  2729. {
  2730. objectWorldTr[i] = tr*objectLocalTr[i];
  2731. }
  2732. // Table area
  2733. loadUrdf("table/table.urdf", objectWorldTr[0].getOrigin(), objectWorldTr[0].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2734. loadUrdf("tray.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2735. //loadUrdf("cup_small.urdf", objectWorldTr[2].getOrigin(), objectWorldTr[2].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2736. //loadUrdf("pitcher_small.urdf", objectWorldTr[3].getOrigin(), objectWorldTr[3].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2737. loadUrdf("teddy_vhacd.urdf", objectWorldTr[4].getOrigin(), objectWorldTr[4].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2738. loadUrdf("cube_small.urdf", objectWorldTr[5].getOrigin(), objectWorldTr[5].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2739. loadUrdf("sphere_small.urdf", objectWorldTr[6].getOrigin(), objectWorldTr[6].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2740. loadUrdf("duck_vhacd.urdf", objectWorldTr[7].getOrigin(), objectWorldTr[7].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2741. //loadUrdf("Apple/apple.urdf", objectWorldTr[8].getOrigin(), objectWorldTr[8].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2742. // Shelf area
  2743. loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
  2744. loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2745. loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2746. loadUrdf("cube_small.urdf", btVector3(0.3, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2747. // Chess area
  2748. loadUrdf("table_square/table_square.urdf", btVector3(-1.0, 0, 0.0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2749. //loadUrdf("pawn.urdf", btVector3(-0.8, -0.1, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2750. //loadUrdf("queen.urdf", btVector3(-0.9, -0.2, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2751. //loadUrdf("king.urdf", btVector3(-1.0, 0, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2752. //loadUrdf("bishop.urdf", btVector3(-1.1, 0.1, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2753. //loadUrdf("rook.urdf", btVector3(-1.2, 0, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2754. //loadUrdf("knight.urdf", btVector3(-1.2, 0.2, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2755. //loadUrdf("husky/husky.urdf", btVector3(2, -5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
  2756. m_data->m_huskyId = bodyId;
  2757. m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
  2758. }
  2759. if (m_data->m_kukaGripperFixed && m_data->m_kukaGripperMultiBody)
  2760. {
  2761. InteralBodyData* childBody = m_data->getHandle(m_data->m_gripperId);
  2762. // Add gripper controller
  2763. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)childBody->m_multiBody->getLink(1).m_userPtr;
  2764. if (motor)
  2765. {
  2766. btScalar posTarget = (-0.048)*btMin(btScalar(0.75), gVRGripper2Analog) / 0.75;
  2767. motor->setPositionTarget(posTarget, .2);
  2768. motor->setVelocityTarget(0.0, .5);
  2769. motor->setMaxAppliedImpulse(5.0);
  2770. }
  2771. }
  2772. if (m_data->m_gripperRigidbodyFixed && m_data->m_gripperMultiBody)
  2773. {
  2774. m_data->m_gripperRigidbodyFixed->setFrameInB(btMatrix3x3(gVRGripperOrn));
  2775. m_data->m_gripperRigidbodyFixed->setPivotInB(gVRGripperPos);
  2776. for (int i = 0; i < m_data->m_gripperMultiBody->getNumLinks(); i++)
  2777. {
  2778. if (supportsJointMotor(m_data->m_gripperMultiBody, i))
  2779. {
  2780. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)m_data->m_gripperMultiBody->getLink(i ).m_userPtr;
  2781. if (motor)
  2782. {
  2783. motor->setErp(0.2);
  2784. btScalar posTarget = 0.1 + (1 - btMin(btScalar(0.75),gVRGripperAnalog)*btScalar(1.5))*SIMD_HALF_PI*0.29;
  2785. btScalar maxPosTarget = 0.55;
  2786. if (m_data->m_gripperMultiBody->getJointPos(i) < 0)
  2787. {
  2788. m_data->m_gripperMultiBody->setJointPos(i,0);
  2789. }
  2790. if (m_data->m_gripperMultiBody->getJointPos(i) > maxPosTarget)
  2791. {
  2792. m_data->m_gripperMultiBody->setJointPos(i, maxPosTarget);
  2793. }
  2794. motor->setPositionTarget(posTarget, 1);
  2795. motor->setVelocityTarget(0, 0.5);
  2796. btScalar maxImp = 1*m_data->m_physicsDeltaTime;
  2797. motor->setMaxAppliedImpulse(maxImp);
  2798. //motor->setRhsClamp(gRhsClamp);
  2799. }
  2800. }
  2801. }
  2802. }
  2803. // Inverse kinematics for KUKA
  2804. //if (0)
  2805. {
  2806. InternalBodyHandle* bodyHandle = m_data->getHandle(m_data->m_KukaId);
  2807. if (bodyHandle && bodyHandle->m_multiBody && bodyHandle->m_multiBody->getNumDofs()==7)
  2808. {
  2809. btMultiBody* mb = bodyHandle->m_multiBody;
  2810. btScalar sqLen = (mb->getBaseWorldTransform().getOrigin() - gVRController2Pos).length2();
  2811. btScalar distanceThreshold = 1.3;
  2812. gCloseToKuka=(sqLen<(distanceThreshold*distanceThreshold));
  2813. int numDofs = bodyHandle->m_multiBody->getNumDofs();
  2814. btAlignedObjectArray<double> q_new;
  2815. btAlignedObjectArray<double> q_current;
  2816. q_current.resize(numDofs);
  2817. for (int i = 0; i < numDofs; i++)
  2818. {
  2819. q_current[i] = bodyHandle->m_multiBody->getJointPos(i);
  2820. }
  2821. q_new.resize(numDofs);
  2822. //sensible rest-pose
  2823. q_new[0] = 0;// -SIMD_HALF_PI;
  2824. q_new[1] = 0;
  2825. q_new[2] = 0;
  2826. q_new[3] = SIMD_HALF_PI;
  2827. q_new[4] = 0;
  2828. q_new[5] = -SIMD_HALF_PI*0.66;
  2829. q_new[6] = 0;
  2830. if (gCloseToKuka)
  2831. {
  2832. double dampIk[6] = {1.0, 1.0, 1.0, 1.0, 1.0, 0.0};
  2833. IKTrajectoryHelper** ikHelperPtrPtr = m_data->m_inverseKinematicsHelpers.find(bodyHandle->m_multiBody);
  2834. IKTrajectoryHelper* ikHelperPtr = 0;
  2835. if (ikHelperPtrPtr)
  2836. {
  2837. ikHelperPtr = *ikHelperPtrPtr;
  2838. }
  2839. else
  2840. {
  2841. IKTrajectoryHelper* tmpHelper = new IKTrajectoryHelper;
  2842. m_data->m_inverseKinematicsHelpers.insert(bodyHandle->m_multiBody, tmpHelper);
  2843. ikHelperPtr = tmpHelper;
  2844. }
  2845. int endEffectorLinkIndex = 6;
  2846. if (ikHelperPtr && (endEffectorLinkIndex<bodyHandle->m_multiBody->getNumLinks()))
  2847. {
  2848. b3AlignedObjectArray<double> jacobian_linear;
  2849. jacobian_linear.resize(3*numDofs);
  2850. b3AlignedObjectArray<double> jacobian_angular;
  2851. jacobian_angular.resize(3*numDofs);
  2852. int jacSize = 0;
  2853. btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
  2854. if (tree)
  2855. {
  2856. jacSize = jacobian_linear.size();
  2857. // Set jacobian value
  2858. int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
  2859. btInverseDynamics::vecx nu(numDofs+baseDofs), qdot(numDofs + baseDofs), q(numDofs + baseDofs), joint_force(numDofs + baseDofs);
  2860. for (int i = 0; i < numDofs; i++)
  2861. {
  2862. q_current[i] = bodyHandle->m_multiBody->getJointPos(i);
  2863. q[i+baseDofs] = bodyHandle->m_multiBody->getJointPos(i);
  2864. qdot[i + baseDofs] = 0;
  2865. nu[i+baseDofs] = 0;
  2866. }
  2867. // Set the gravity to correspond to the world gravity
  2868. btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
  2869. if (-1 != tree->setGravityInWorldFrame(id_grav) &&
  2870. -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
  2871. {
  2872. tree->calculateJacobians(q);
  2873. btInverseDynamics::mat3x jac_t(3,numDofs);
  2874. btInverseDynamics::mat3x jac_r(3,numDofs);
  2875. tree->getBodyJacobianTrans(endEffectorLinkIndex, &jac_t);
  2876. tree->getBodyJacobianRot(endEffectorLinkIndex, &jac_r);
  2877. for (int i = 0; i < 3; ++i)
  2878. {
  2879. for (int j = 0; j < numDofs; ++j)
  2880. {
  2881. jacobian_linear[i*numDofs+j] = jac_t(i,j);
  2882. jacobian_angular[i*numDofs+j] = jac_r(i,j);
  2883. }
  2884. }
  2885. }
  2886. }
  2887. int ikMethod= IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE;//IK2_VEL_DLS_WITH_ORIENTATION; //IK2_VEL_DLS;
  2888. btVector3DoubleData endEffectorWorldPosition;
  2889. btVector3DoubleData endEffectorWorldOrientation;
  2890. btVector3DoubleData targetWorldPosition;
  2891. btVector3DoubleData targetWorldOrientation;
  2892. btVector3 endEffectorPosWorld = bodyHandle->m_multiBody->getLink(endEffectorLinkIndex).m_cachedWorldTransform.getOrigin();
  2893. btQuaternion endEffectorOriWorld = bodyHandle->m_multiBody->getLink(endEffectorLinkIndex).m_cachedWorldTransform.getRotation();
  2894. btVector4 endEffectorOri(endEffectorOriWorld.x(),endEffectorOriWorld.y(),endEffectorOriWorld.z(),endEffectorOriWorld.w());
  2895. // Prescribed position and orientation
  2896. static btScalar time=0.f;
  2897. time+=0.01;
  2898. btVector3 targetPos(0.4-0.4*b3Cos( time), 0, 0.8+0.4*b3Cos( time));
  2899. targetPos +=mb->getBasePos();
  2900. btVector4 downOrn(0,1,0,0);
  2901. // Controller orientation
  2902. btVector4 controllerOrn(gVRController2Orn.x(), gVRController2Orn.y(), gVRController2Orn.z(), gVRController2Orn.w());
  2903. // Set position and orientation
  2904. endEffectorPosWorld.serializeDouble(endEffectorWorldPosition);
  2905. endEffectorOri.serializeDouble(endEffectorWorldOrientation);
  2906. downOrn.serializeDouble(targetWorldOrientation);
  2907. //targetPos.serializeDouble(targetWorldPosition);
  2908. gVRController2Pos.serializeDouble(targetWorldPosition);
  2909. //controllerOrn.serializeDouble(targetWorldOrientation);
  2910. if (ikMethod == IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE)
  2911. {
  2912. btAlignedObjectArray<double> lower_limit;
  2913. btAlignedObjectArray<double> upper_limit;
  2914. btAlignedObjectArray<double> joint_range;
  2915. btAlignedObjectArray<double> rest_pose;
  2916. lower_limit.resize(numDofs);
  2917. upper_limit.resize(numDofs);
  2918. joint_range.resize(numDofs);
  2919. rest_pose.resize(numDofs);
  2920. lower_limit[0] = -.967;
  2921. lower_limit[1] = -2.0;
  2922. lower_limit[2] = -2.96;
  2923. lower_limit[3] = 0.19;
  2924. lower_limit[4] = -2.96;
  2925. lower_limit[5] = -2.09;
  2926. lower_limit[6] = -3.05;
  2927. upper_limit[0] = .96;
  2928. upper_limit[1] = 2.0;
  2929. upper_limit[2] = 2.96;
  2930. upper_limit[3] = 2.29;
  2931. upper_limit[4] = 2.96;
  2932. upper_limit[5] = 2.09;
  2933. upper_limit[6] = 3.05;
  2934. joint_range[0] = 5.8;
  2935. joint_range[1] = 4;
  2936. joint_range[2] = 5.8;
  2937. joint_range[3] = 4;
  2938. joint_range[4] = 5.8;
  2939. joint_range[5] = 4;
  2940. joint_range[6] = 6;
  2941. rest_pose[0] = 0;
  2942. rest_pose[1] = 0;
  2943. rest_pose[2] = 0;
  2944. rest_pose[3] = SIMD_HALF_PI;
  2945. rest_pose[4] = 0;
  2946. rest_pose[5] = -SIMD_HALF_PI*0.66;
  2947. rest_pose[6] = 0;
  2948. ikHelperPtr->computeNullspaceVel(numDofs, &q_current[0], &lower_limit[0], &upper_limit[0], &joint_range[0], &rest_pose[0]);
  2949. }
  2950. ikHelperPtr->computeIK(targetWorldPosition.m_floats, targetWorldOrientation.m_floats,
  2951. endEffectorWorldPosition.m_floats, endEffectorWorldOrientation.m_floats,
  2952. &q_current[0],
  2953. numDofs, endEffectorLinkIndex,
  2954. &q_new[0], ikMethod, &jacobian_linear[0], &jacobian_angular[0], jacSize*2, dampIk);
  2955. }
  2956. }
  2957. //directly set the position of the links, only for debugging IK, don't use this method!
  2958. if (0)
  2959. {
  2960. for (int i=0;i<mb->getNumLinks();i++)
  2961. {
  2962. btScalar desiredPosition = q_new[i];
  2963. mb->setJointPosMultiDof(i,&desiredPosition);
  2964. }
  2965. } else
  2966. {
  2967. int numMotors = 0;
  2968. //find the joint motors and apply the desired velocity and maximum force/torque
  2969. {
  2970. int velIndex = 6;//skip the 3 linear + 3 angular degree of freedom velocity entries of the base
  2971. int posIndex = 7;//skip 3 positional and 4 orientation (quaternion) positional degrees of freedom of the base
  2972. for (int link=0;link<mb->getNumLinks();link++)
  2973. {
  2974. if (supportsJointMotor(mb,link))
  2975. {
  2976. btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr;
  2977. if (motor)
  2978. {
  2979. btScalar desiredVelocity = 0.f;
  2980. btScalar desiredPosition = q_new[link];
  2981. motor->setRhsClamp(gRhsClamp);
  2982. //printf("link %d: %f", link, q_new[link]);
  2983. motor->setVelocityTarget(desiredVelocity,1.0);
  2984. motor->setPositionTarget(desiredPosition,0.6);
  2985. btScalar maxImp = 1.0;
  2986. motor->setMaxAppliedImpulse(maxImp);
  2987. numMotors++;
  2988. }
  2989. }
  2990. velIndex += mb->getLink(link).m_dofCount;
  2991. posIndex += mb->getLink(link).m_posVarCount;
  2992. }
  2993. }
  2994. }
  2995. }
  2996. }
  2997. }
  2998. int maxSteps = m_data->m_numSimulationSubSteps+3;
  2999. if (m_data->m_numSimulationSubSteps)
  3000. {
  3001. gSubStep = m_data->m_physicsDeltaTime / m_data->m_numSimulationSubSteps;
  3002. }
  3003. else
  3004. {
  3005. gSubStep = m_data->m_physicsDeltaTime;
  3006. }
  3007. int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);
  3008. gDroppedSimulationSteps += numSteps > maxSteps ? numSteps - maxSteps : 0;
  3009. if (numSteps)
  3010. {
  3011. gNumSteps = numSteps;
  3012. gDtInSec = dtInSec;
  3013. }
  3014. }
  3015. }
  3016. void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
  3017. {
  3018. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  3019. if (body) {
  3020. btMultiBody* mb = body->m_multiBody;
  3021. if (mb) {
  3022. for (int l=0;l<mb->getNumLinks();l++) {
  3023. for (int d=0;d<mb->getLink(l).m_dofCount;d++) {
  3024. double damping_coefficient = mb->getLink(l).m_jointDamping;
  3025. double damping = -damping_coefficient*mb->getJointVelMultiDof(l)[d];
  3026. mb->addJointTorqueMultiDof(l, d, damping);
  3027. }
  3028. }
  3029. }
  3030. }
  3031. }