PhysicsServerCommandProcessor.cpp 61 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812
  1. #include "PhysicsServerCommandProcessor.h"
  2. #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
  3. #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
  4. #include "../Importers/ImportURDFDemo/URDF2Bullet.h"
  5. #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
  6. #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
  7. #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
  8. #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
  9. #include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h"
  10. #include "../CommonInterfaces/CommonRenderInterface.h"
  11. #include "btBulletDynamicsCommon.h"
  12. #include "LinearMath/btTransform.h"
  13. #include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
  14. #include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
  15. #include "LinearMath/btSerializer.h"
  16. #include "Bullet3Common/b3Logging.h"
  17. #include "../CommonInterfaces/CommonGUIHelperInterface.h"
  18. #include "SharedMemoryCommands.h"
  19. struct UrdfLinkNameMapUtil
  20. {
  21. btMultiBody* m_mb;
  22. btDefaultSerializer* m_memSerializer;
  23. UrdfLinkNameMapUtil():m_mb(0),m_memSerializer(0)
  24. {
  25. }
  26. };
  27. struct SharedMemoryDebugDrawer : public btIDebugDraw
  28. {
  29. int m_debugMode;
  30. btAlignedObjectArray<SharedMemLines> m_lines2;
  31. SharedMemoryDebugDrawer ()
  32. :m_debugMode(0)
  33. {
  34. }
  35. virtual void drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color)
  36. {
  37. }
  38. virtual void reportErrorWarning(const char* warningString)
  39. {
  40. }
  41. virtual void draw3dText(const btVector3& location,const char* textString)
  42. {
  43. }
  44. virtual void setDebugMode(int debugMode)
  45. {
  46. m_debugMode = debugMode;
  47. }
  48. virtual int getDebugMode() const
  49. {
  50. return m_debugMode;
  51. }
  52. virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color)
  53. {
  54. SharedMemLines line;
  55. line.m_from = from;
  56. line.m_to = to;
  57. line.m_color = color;
  58. m_lines2.push_back(line);
  59. }
  60. };
  61. struct InteralBodyData
  62. {
  63. btMultiBody* m_multiBody;
  64. btRigidBody* m_rigidBody;
  65. int m_testData;
  66. btTransform m_rootLocalInertialFrame;
  67. InteralBodyData()
  68. :m_multiBody(0),
  69. m_rigidBody(0),
  70. m_testData(0)
  71. {
  72. m_rootLocalInertialFrame.setIdentity();
  73. }
  74. };
  75. ///todo: templatize this
  76. struct InternalBodyHandle : public InteralBodyData
  77. {
  78. BT_DECLARE_ALIGNED_ALLOCATOR();
  79. int m_nextFreeHandle;
  80. void SetNextFree(int next)
  81. {
  82. m_nextFreeHandle = next;
  83. }
  84. int GetNextFree() const
  85. {
  86. return m_nextFreeHandle;
  87. }
  88. };
  89. class btCommandChunk
  90. {
  91. public:
  92. int m_chunkCode;
  93. int m_length;
  94. void *m_oldPtr;
  95. int m_dna_nr;
  96. int m_number;
  97. };
  98. class bCommandChunkPtr4
  99. {
  100. public:
  101. bCommandChunkPtr4(){}
  102. int code;
  103. int len;
  104. union
  105. {
  106. int m_uniqueInt;
  107. };
  108. int dna_nr;
  109. int nr;
  110. };
  111. // ----------------------------------------------------- //
  112. class bCommandChunkPtr8
  113. {
  114. public:
  115. bCommandChunkPtr8(){}
  116. int code, len;
  117. union
  118. {
  119. int m_uniqueInts[2];
  120. };
  121. int dna_nr, nr;
  122. };
  123. struct CommandLogger
  124. {
  125. FILE* m_file;
  126. void writeHeader(unsigned char* buffer) const
  127. {
  128. #ifdef BT_USE_DOUBLE_PRECISION
  129. memcpy(buffer, "BT3CMDd", 7);
  130. #else
  131. memcpy(buffer, "BT3CMDf", 7);
  132. #endif //BT_USE_DOUBLE_PRECISION
  133. int littleEndian= 1;
  134. littleEndian= ((char*)&littleEndian)[0];
  135. if (sizeof(void*)==8)
  136. {
  137. buffer[7] = '-';
  138. } else
  139. {
  140. buffer[7] = '_';
  141. }
  142. if (littleEndian)
  143. {
  144. buffer[8]='v';
  145. } else
  146. {
  147. buffer[8]='V';
  148. }
  149. buffer[9] = 0;
  150. buffer[10] = 0;
  151. buffer[11] = 0;
  152. int ver = btGetVersion();
  153. if (ver>=0 && ver<999)
  154. {
  155. sprintf((char*)&buffer[9],"%d",ver);
  156. }
  157. }
  158. void logCommand(const SharedMemoryCommand& command)
  159. {
  160. btCommandChunk chunk;
  161. chunk.m_chunkCode = command.m_type;
  162. chunk.m_oldPtr = 0;
  163. chunk.m_dna_nr = 0;
  164. chunk.m_length = sizeof(SharedMemoryCommand);
  165. chunk.m_number = 1;
  166. fwrite((const char*)&chunk,sizeof(btCommandChunk), 1,m_file);
  167. fwrite((const char*)&command,sizeof(SharedMemoryCommand),1,m_file);
  168. }
  169. CommandLogger(const char* fileName)
  170. {
  171. m_file = fopen(fileName,"wb");
  172. unsigned char buf[15];
  173. buf[12] = 12;
  174. buf[13] = 13;
  175. buf[14] = 14;
  176. writeHeader(buf);
  177. fwrite(buf,12,1,m_file);
  178. }
  179. virtual ~CommandLogger()
  180. {
  181. fclose(m_file);
  182. }
  183. };
  184. struct CommandLogPlayback
  185. {
  186. unsigned char m_header[12];
  187. FILE* m_file;
  188. bool m_bitsVary;
  189. bool m_fileIs64bit;
  190. CommandLogPlayback(const char* fileName)
  191. {
  192. m_file = fopen(fileName,"rb");
  193. if (m_file)
  194. {
  195. fread(m_header,12,1,m_file);
  196. }
  197. unsigned char c = m_header[7];
  198. m_fileIs64bit = (c=='-');
  199. const bool VOID_IS_8 = ((sizeof(void*)==8));
  200. m_bitsVary = (VOID_IS_8 != m_fileIs64bit);
  201. }
  202. virtual ~CommandLogPlayback()
  203. {
  204. if (m_file)
  205. {
  206. fclose(m_file);
  207. m_file=0;
  208. }
  209. }
  210. bool processNextCommand(SharedMemoryCommand* cmd)
  211. {
  212. if (m_file)
  213. {
  214. size_t s = 0;
  215. if (m_fileIs64bit)
  216. {
  217. bCommandChunkPtr8 chunk8;
  218. s = fread((void*)&chunk8,sizeof(bCommandChunkPtr8),1,m_file);
  219. } else
  220. {
  221. bCommandChunkPtr4 chunk4;
  222. s = fread((void*)&chunk4,sizeof(bCommandChunkPtr4),1,m_file);
  223. }
  224. if (s==1)
  225. {
  226. s = fread(cmd,sizeof(SharedMemoryCommand),1,m_file);
  227. return (s==1);
  228. }
  229. }
  230. return false;
  231. }
  232. };
  233. struct PhysicsServerCommandProcessorInternalData
  234. {
  235. ///handle management
  236. btAlignedObjectArray<InternalBodyHandle> m_bodyHandles;
  237. int m_numUsedHandles; // number of active handles
  238. int m_firstFreeHandle; // free handles list
  239. InternalBodyHandle* getHandle(int handle)
  240. {
  241. btAssert(handle>=0);
  242. btAssert(handle<m_bodyHandles.size());
  243. if ((handle<0) || (handle>=m_bodyHandles.size()))
  244. {
  245. return 0;
  246. }
  247. return &m_bodyHandles[handle];
  248. }
  249. const InternalBodyHandle* getHandle(int handle) const
  250. {
  251. return &m_bodyHandles[handle];
  252. }
  253. void increaseHandleCapacity(int extraCapacity)
  254. {
  255. int curCapacity = m_bodyHandles.size();
  256. btAssert(curCapacity == m_numUsedHandles);
  257. int newCapacity = curCapacity + extraCapacity;
  258. m_bodyHandles.resize(newCapacity);
  259. {
  260. for (int i = curCapacity; i < newCapacity; i++)
  261. m_bodyHandles[i].SetNextFree(i + 1);
  262. m_bodyHandles[newCapacity - 1].SetNextFree(-1);
  263. }
  264. m_firstFreeHandle = curCapacity;
  265. }
  266. void initHandles()
  267. {
  268. m_numUsedHandles = 0;
  269. m_firstFreeHandle = -1;
  270. increaseHandleCapacity(1);
  271. }
  272. void exitHandles()
  273. {
  274. m_bodyHandles.resize(0);
  275. m_firstFreeHandle = -1;
  276. m_numUsedHandles = 0;
  277. }
  278. int allocHandle()
  279. {
  280. btAssert(m_firstFreeHandle>=0);
  281. int handle = m_firstFreeHandle;
  282. m_firstFreeHandle = getHandle(handle)->GetNextFree();
  283. m_numUsedHandles++;
  284. if (m_firstFreeHandle<0)
  285. {
  286. int curCapacity = m_bodyHandles.size();
  287. int additionalCapacity= m_bodyHandles.size();
  288. increaseHandleCapacity(additionalCapacity);
  289. getHandle(handle)->SetNextFree(m_firstFreeHandle);
  290. }
  291. return handle;
  292. }
  293. void freeHandle(int handle)
  294. {
  295. btAssert(handle >= 0);
  296. getHandle(handle)->SetNextFree(m_firstFreeHandle);
  297. m_firstFreeHandle = handle;
  298. m_numUsedHandles--;
  299. }
  300. ///end handle management
  301. CommandLogger* m_commandLogger;
  302. CommandLogPlayback* m_logPlayback;
  303. btScalar m_physicsDeltaTime;
  304. btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks;
  305. btAlignedObjectArray<btBulletWorldImporter*> m_worldImporters;
  306. btAlignedObjectArray<UrdfLinkNameMapUtil*> m_urdfLinkNameMapper;
  307. btHashMap<btHashInt, btMultiBodyJointMotor*> m_multiBodyJointMotorMap;
  308. btAlignedObjectArray<std::string*> m_strings;
  309. btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
  310. btBroadphaseInterface* m_broadphase;
  311. btCollisionDispatcher* m_dispatcher;
  312. btMultiBodyConstraintSolver* m_solver;
  313. btDefaultCollisionConfiguration* m_collisionConfiguration;
  314. btMultiBodyDynamicsWorld* m_dynamicsWorld;
  315. SharedMemoryDebugDrawer* m_remoteDebugDrawer;
  316. struct GUIHelperInterface* m_guiHelper;
  317. int m_sharedMemoryKey;
  318. bool m_verboseOutput;
  319. //data for picking objects
  320. class btRigidBody* m_pickedBody;
  321. class btTypedConstraint* m_pickedConstraint;
  322. class btMultiBodyPoint2Point* m_pickingMultiBodyPoint2Point;
  323. btVector3 m_oldPickingPos;
  324. btVector3 m_hitPos;
  325. btScalar m_oldPickingDist;
  326. bool m_prevCanSleep;
  327. PhysicsServerCommandProcessorInternalData()
  328. :
  329. m_commandLogger(0),
  330. m_logPlayback(0),
  331. m_physicsDeltaTime(1./240.),
  332. m_dynamicsWorld(0),
  333. m_remoteDebugDrawer(0),
  334. m_guiHelper(0),
  335. m_sharedMemoryKey(SHARED_MEMORY_KEY),
  336. m_verboseOutput(false),
  337. m_pickedBody(0),
  338. m_pickedConstraint(0),
  339. m_pickingMultiBodyPoint2Point(0)
  340. {
  341. initHandles();
  342. #if 0
  343. btAlignedObjectArray<int> bla;
  344. for (int i=0;i<1024;i++)
  345. {
  346. int handle = allocHandle();
  347. bla.push_back(handle);
  348. InternalBodyHandle* body = getHandle(handle);
  349. InteralBodyData* body2 = body;
  350. }
  351. for (int i=0;i<bla.size();i++)
  352. {
  353. freeHandle(bla[i]);
  354. }
  355. bla.resize(0);
  356. for (int i=0;i<1024;i++)
  357. {
  358. int handle = allocHandle();
  359. bla.push_back(handle);
  360. InternalBodyHandle* body = getHandle(handle);
  361. InteralBodyData* body2 = body;
  362. }
  363. for (int i=0;i<bla.size();i++)
  364. {
  365. freeHandle(bla[i]);
  366. }
  367. bla.resize(0);
  368. for (int i=0;i<1024;i++)
  369. {
  370. int handle = allocHandle();
  371. bla.push_back(handle);
  372. InternalBodyHandle* body = getHandle(handle);
  373. InteralBodyData* body2 = body;
  374. }
  375. for (int i=0;i<bla.size();i++)
  376. {
  377. freeHandle(bla[i]);
  378. }
  379. #endif
  380. }
  381. };
  382. void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper)
  383. {
  384. if (guiHelper)
  385. {
  386. guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
  387. } else
  388. {
  389. if (m_data->m_guiHelper && m_data->m_dynamicsWorld && m_data->m_dynamicsWorld->getDebugDrawer())
  390. {
  391. m_data->m_dynamicsWorld->setDebugDrawer(0);
  392. }
  393. }
  394. m_data->m_guiHelper = guiHelper;
  395. }
  396. PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
  397. {
  398. m_data = new PhysicsServerCommandProcessorInternalData();
  399. createEmptyDynamicsWorld();
  400. }
  401. PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
  402. {
  403. deleteDynamicsWorld();
  404. if (m_data->m_commandLogger)
  405. {
  406. delete m_data->m_commandLogger;
  407. m_data->m_commandLogger = 0;
  408. }
  409. delete m_data;
  410. }
  411. void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
  412. {
  413. ///collision configuration contains default setup for memory, collision setup
  414. m_data->m_collisionConfiguration = new btDefaultCollisionConfiguration();
  415. //m_collisionConfiguration->setConvexConvexMultipointIterations();
  416. ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
  417. m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration);
  418. m_data->m_broadphase = new btDbvtBroadphase();
  419. m_data->m_solver = new btMultiBodyConstraintSolver;
  420. m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
  421. m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
  422. m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
  423. }
  424. void PhysicsServerCommandProcessor::deleteDynamicsWorld()
  425. {
  426. for (int i=0;i<m_data->m_multiBodyJointFeedbacks.size();i++)
  427. {
  428. delete m_data->m_multiBodyJointFeedbacks[i];
  429. }
  430. m_data->m_multiBodyJointFeedbacks.clear();
  431. for (int i=0;i<m_data->m_worldImporters.size();i++)
  432. {
  433. delete m_data->m_worldImporters[i];
  434. }
  435. m_data->m_worldImporters.clear();
  436. for (int i=0;i<m_data->m_urdfLinkNameMapper.size();i++)
  437. {
  438. delete m_data->m_urdfLinkNameMapper[i];
  439. }
  440. m_data->m_urdfLinkNameMapper.clear();
  441. m_data->m_multiBodyJointMotorMap.clear();
  442. for (int i=0;i<m_data->m_strings.size();i++)
  443. {
  444. delete m_data->m_strings[i];
  445. }
  446. m_data->m_strings.clear();
  447. if (m_data->m_dynamicsWorld)
  448. {
  449. int i;
  450. for (i = m_data->m_dynamicsWorld->getNumConstraints() - 1; i >= 0; i--)
  451. {
  452. m_data->m_dynamicsWorld->removeConstraint(m_data->m_dynamicsWorld->getConstraint(i));
  453. }
  454. for (i = m_data->m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
  455. {
  456. btCollisionObject* obj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
  457. btRigidBody* body = btRigidBody::upcast(obj);
  458. if (body && body->getMotionState())
  459. {
  460. delete body->getMotionState();
  461. }
  462. m_data->m_dynamicsWorld->removeCollisionObject(obj);
  463. delete obj;
  464. }
  465. }
  466. //delete collision shapes
  467. for (int j = 0; j<m_data->m_collisionShapes.size(); j++)
  468. {
  469. btCollisionShape* shape = m_data->m_collisionShapes[j];
  470. delete shape;
  471. }
  472. m_data->m_collisionShapes.clear();
  473. delete m_data->m_dynamicsWorld;
  474. m_data->m_dynamicsWorld=0;
  475. delete m_data->m_remoteDebugDrawer;
  476. m_data->m_remoteDebugDrawer =0;
  477. delete m_data->m_solver;
  478. m_data->m_solver=0;
  479. delete m_data->m_broadphase;
  480. m_data->m_broadphase=0;
  481. delete m_data->m_dispatcher;
  482. m_data->m_dispatcher=0;
  483. delete m_data->m_collisionConfiguration;
  484. m_data->m_collisionConfiguration=0;
  485. }
  486. bool PhysicsServerCommandProcessor::supportsJointMotor(btMultiBody* mb, int mbLinkIndex)
  487. {
  488. bool canHaveMotor = (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute
  489. ||mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::ePrismatic);
  490. return canHaveMotor;
  491. }
  492. //for testing, create joint motors for revolute and prismatic joints
  493. void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb)
  494. {
  495. int numLinks = mb->getNumLinks();
  496. for (int i=0;i<numLinks;i++)
  497. {
  498. int mbLinkIndex = i;
  499. if (supportsJointMotor(mb,mbLinkIndex))
  500. {
  501. float maxMotorImpulse = 0.f;
  502. int dof = 0;
  503. btScalar desiredVelocity = 0.f;
  504. btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,dof,desiredVelocity,maxMotorImpulse);
  505. //motor->setMaxAppliedImpulse(0);
  506. m_data->m_multiBodyJointMotorMap.insert(mbLinkIndex,motor);
  507. m_data->m_dynamicsWorld->addMultiBodyConstraint(motor);
  508. }
  509. }
  510. }
  511. bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
  512. bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes)
  513. {
  514. btAssert(m_data->m_dynamicsWorld);
  515. if (!m_data->m_dynamicsWorld)
  516. {
  517. b3Error("loadUrdf: No valid m_dynamicsWorld");
  518. return false;
  519. }
  520. BulletURDFImporter u2b(m_data->m_guiHelper);
  521. bool loadOk = u2b.loadURDF(fileName, useFixedBase);
  522. if (loadOk)
  523. {
  524. //get a body index
  525. int bodyUniqueId = m_data->allocHandle();
  526. if (bodyUniqueIdPtr)
  527. *bodyUniqueIdPtr= bodyUniqueId;
  528. InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
  529. {
  530. btScalar mass = 0;
  531. bodyHandle->m_rootLocalInertialFrame.setIdentity();
  532. btVector3 localInertiaDiagonal(0,0,0);
  533. int urdfLinkIndex = u2b.getRootLinkIndex();
  534. u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
  535. }
  536. if (m_data->m_verboseOutput)
  537. {
  538. b3Printf("loaded %s OK!", fileName);
  539. }
  540. btTransform tr;
  541. tr.setIdentity();
  542. tr.setOrigin(pos);
  543. tr.setRotation(orn);
  544. //int rootLinkIndex = u2b.getRootLinkIndex();
  545. // printf("urdf root link index = %d\n",rootLinkIndex);
  546. MyMultiBodyCreator creation(m_data->m_guiHelper);
  547. ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
  548. btMultiBody* mb = creation.getBulletMultiBody();
  549. if (useMultiBody)
  550. {
  551. if (mb)
  552. {
  553. bodyHandle->m_multiBody = mb;
  554. createJointMotors(mb);
  555. //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
  556. UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
  557. m_data->m_urdfLinkNameMapper.push_back(util);
  558. util->m_mb = mb;
  559. util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient);
  560. //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
  561. util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0);
  562. for (int i=0;i<mb->getNumLinks();i++)
  563. {
  564. //disable serialization of the collision objects
  565. util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0);
  566. int urdfLinkIndex = creation.m_mb2urdfLink[i];
  567. std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str());
  568. m_data->m_strings.push_back(linkName);
  569. util->m_memSerializer->registerNameForPointer(linkName->c_str(),linkName->c_str());
  570. mb->getLink(i).m_linkName = linkName->c_str();
  571. std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str());
  572. m_data->m_strings.push_back(jointName);
  573. util->m_memSerializer->registerNameForPointer(jointName->c_str(),jointName->c_str());
  574. mb->getLink(i).m_jointName = jointName->c_str();
  575. }
  576. std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
  577. m_data->m_strings.push_back(baseName);
  578. util->m_memSerializer->registerNameForPointer(baseName->c_str(),baseName->c_str());
  579. mb->setBaseName(baseName->c_str());
  580. util->m_memSerializer->insertHeader();
  581. int len = mb->calculateSerializeBufferSize();
  582. btChunk* chunk = util->m_memSerializer->allocate(len,1);
  583. const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer);
  584. util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb);
  585. return true;
  586. } else
  587. {
  588. b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later.");
  589. return false;
  590. }
  591. } else
  592. {
  593. btAssert(0);
  594. return true;
  595. }
  596. }
  597. return false;
  598. }
  599. bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
  600. {
  601. bool hasStatus = false;
  602. {
  603. #if 0
  604. if (m_data->m_logPlayback)
  605. {
  606. if (m_data->m_testBlock1->m_numServerCommands>m_data->m_testBlock1->m_numProcessedServerCommands)
  607. {
  608. m_data->m_testBlock1->m_numProcessedServerCommands++;
  609. }
  610. //push a command from log file
  611. bool hasCommand = m_data->m_logPlayback->processNextCommand(&m_data->m_testBlock1->m_clientCommands[0]);
  612. if (hasCommand)
  613. {
  614. m_data->m_testBlock1->m_numClientCommands++;
  615. }
  616. }
  617. #endif
  618. ///we ignore overflow of integer for now
  619. {
  620. //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands
  621. //const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0];
  622. #if 0
  623. if (m_data->m_commandLogger)
  624. {
  625. m_data->m_commandLogger->logCommand(m_data->m_testBlock1);
  626. }
  627. #endif
  628. //m_data->m_testBlock1->m_numProcessedClientCommands++;
  629. //no timestamp yet
  630. int timeStamp = 0;
  631. //consume the command
  632. switch (clientCmd.m_type)
  633. {
  634. #if 0
  635. case CMD_SEND_BULLET_DATA_STREAM:
  636. {
  637. if (m_data->m_verboseOutput)
  638. {
  639. b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength);
  640. }
  641. btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
  642. m_data->m_worldImporters.push_back(worldImporter);
  643. bool completedOk = worldImporter->loadFileFromMemory(m_data->m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength);
  644. if (completedOk)
  645. {
  646. SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
  647. m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
  648. m_data->submitServerStatus(status);
  649. } else
  650. {
  651. SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,clientCmd.m_sequenceNumber,timeStamp);
  652. m_data->submitServerStatus(status);
  653. }
  654. break;
  655. }
  656. #endif
  657. case CMD_REQUEST_DEBUG_LINES:
  658. {
  659. int curFlags =m_data->m_remoteDebugDrawer->getDebugMode();
  660. int debugMode = clientCmd.m_requestDebugLinesArguments.m_debugMode;//clientCmd.btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb;
  661. int startingLineIndex = clientCmd.m_requestDebugLinesArguments.m_startingLineIndex;
  662. if (startingLineIndex<0)
  663. {
  664. b3Warning("startingLineIndex should be non-negative");
  665. startingLineIndex = 0;
  666. }
  667. if (clientCmd.m_requestDebugLinesArguments.m_startingLineIndex==0)
  668. {
  669. m_data->m_remoteDebugDrawer->m_lines2.resize(0);
  670. //|btIDebugDraw::DBG_DrawAabb|
  671. // btIDebugDraw::DBG_DrawConstraints |btIDebugDraw::DBG_DrawConstraintLimits ;
  672. m_data->m_remoteDebugDrawer->setDebugMode(debugMode);
  673. btIDebugDraw* oldDebugDrawer = m_data->m_dynamicsWorld->getDebugDrawer();
  674. m_data->m_dynamicsWorld->setDebugDrawer(m_data->m_remoteDebugDrawer);
  675. m_data->m_dynamicsWorld->debugDrawWorld();
  676. m_data->m_dynamicsWorld->setDebugDrawer(oldDebugDrawer);
  677. m_data->m_remoteDebugDrawer->setDebugMode(curFlags);
  678. }
  679. //9 floats per line: 3 floats for 'from', 3 floats for 'to' and 3 floats for 'color'
  680. int maxNumLines = bufferSizeInBytes/(sizeof(float)*9)-1;
  681. if (startingLineIndex >m_data->m_remoteDebugDrawer->m_lines2.size())
  682. {
  683. b3Warning("m_startingLineIndex exceeds total number of debug lines");
  684. startingLineIndex =m_data->m_remoteDebugDrawer->m_lines2.size();
  685. }
  686. int numLines = btMin(maxNumLines,m_data->m_remoteDebugDrawer->m_lines2.size()-startingLineIndex);
  687. if (numLines)
  688. {
  689. float* linesFrom = (float*)bufferServerToClient;
  690. float* linesTo = (float*)(bufferServerToClient+numLines*3*sizeof(float));
  691. float* linesColor = (float*)(bufferServerToClient+2*numLines*3*sizeof(float));
  692. for (int i=0;i<numLines;i++)
  693. {
  694. linesFrom[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.x();
  695. linesTo[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.x();
  696. linesColor[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.x();
  697. linesFrom[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.y();
  698. linesTo[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.y();
  699. linesColor[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.y();
  700. linesFrom[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.z();
  701. linesTo[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.z();
  702. linesColor[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.z();
  703. }
  704. }
  705. serverStatusOut.m_type = CMD_DEBUG_LINES_COMPLETED;
  706. serverStatusOut.m_sendDebugLinesArgs.m_numDebugLines = numLines;
  707. serverStatusOut.m_sendDebugLinesArgs.m_startingLineIndex = startingLineIndex;
  708. serverStatusOut.m_sendDebugLinesArgs.m_numRemainingDebugLines = m_data->m_remoteDebugDrawer->m_lines2.size()-(startingLineIndex+numLines);
  709. hasStatus = true;
  710. break;
  711. }
  712. case CMD_LOAD_URDF:
  713. {
  714. const UrdfArgs& urdfArgs = clientCmd.m_urdfArguments;
  715. if (m_data->m_verboseOutput)
  716. {
  717. b3Printf("Processed CMD_LOAD_URDF:%s", urdfArgs.m_urdfFileName);
  718. }
  719. btAssert((clientCmd.m_updateFlags&URDF_ARGS_FILE_NAME) !=0);
  720. btAssert(urdfArgs.m_urdfFileName);
  721. btVector3 initialPos(0,0,0);
  722. btQuaternion initialOrn(0,0,0,1);
  723. if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_POSITION)
  724. {
  725. initialPos[0] = urdfArgs.m_initialPosition[0];
  726. initialPos[1] = urdfArgs.m_initialPosition[1];
  727. initialPos[2] = urdfArgs.m_initialPosition[2];
  728. }
  729. if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_ORIENTATION)
  730. {
  731. initialOrn[0] = urdfArgs.m_initialOrientation[0];
  732. initialOrn[1] = urdfArgs.m_initialOrientation[1];
  733. initialOrn[2] = urdfArgs.m_initialOrientation[2];
  734. initialOrn[3] = urdfArgs.m_initialOrientation[3];
  735. }
  736. bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? urdfArgs.m_useMultiBody : true;
  737. bool useFixedBase = (clientCmd.m_updateFlags & URDF_ARGS_USE_FIXED_BASE) ? urdfArgs.m_useFixedBase: false;
  738. int bodyUniqueId;
  739. //load the actual URDF and send a report: completed or failed
  740. bool completedOk = loadUrdf(urdfArgs.m_urdfFileName,
  741. initialPos,initialOrn,
  742. useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes);
  743. if (completedOk)
  744. {
  745. m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
  746. serverStatusOut.m_type = CMD_URDF_LOADING_COMPLETED;
  747. if (m_data->m_urdfLinkNameMapper.size())
  748. {
  749. serverStatusOut.m_dataStreamArguments.m_streamChunkLength = m_data->m_urdfLinkNameMapper.at(m_data->m_urdfLinkNameMapper.size()-1)->m_memSerializer->getCurrentBufferSize();
  750. }
  751. serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = bodyUniqueId;
  752. hasStatus = true;
  753. } else
  754. {
  755. serverStatusOut.m_type = CMD_URDF_LOADING_FAILED;
  756. hasStatus = true;
  757. }
  758. break;
  759. }
  760. case CMD_CREATE_SENSOR:
  761. {
  762. if (m_data->m_verboseOutput)
  763. {
  764. b3Printf("Processed CMD_CREATE_SENSOR");
  765. }
  766. int bodyUniqueId = clientCmd.m_createSensorArguments.m_bodyUniqueId;
  767. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  768. if (body && body->m_multiBody)
  769. {
  770. btMultiBody* mb = body->m_multiBody;
  771. btAssert(mb);
  772. for (int i=0;i<clientCmd.m_createSensorArguments.m_numJointSensorChanges;i++)
  773. {
  774. int jointIndex = clientCmd.m_createSensorArguments.m_jointIndex[i];
  775. if (clientCmd.m_createSensorArguments.m_enableJointForceSensor[i])
  776. {
  777. if (mb->getLink(jointIndex).m_jointFeedback)
  778. {
  779. b3Warning("CMD_CREATE_SENSOR: sensor for joint [%d] already enabled", jointIndex);
  780. } else
  781. {
  782. btMultiBodyJointFeedback* fb = new btMultiBodyJointFeedback();
  783. fb->m_reactionForces.setZero();
  784. mb->getLink(jointIndex).m_jointFeedback = fb;
  785. m_data->m_multiBodyJointFeedbacks.push_back(fb);
  786. };
  787. } else
  788. {
  789. if (mb->getLink(jointIndex).m_jointFeedback)
  790. {
  791. m_data->m_multiBodyJointFeedbacks.remove(mb->getLink(jointIndex).m_jointFeedback);
  792. delete mb->getLink(jointIndex).m_jointFeedback;
  793. mb->getLink(jointIndex).m_jointFeedback=0;
  794. } else
  795. {
  796. b3Warning("CMD_CREATE_SENSOR: cannot perform sensor removal request, no sensor on joint [%d]", jointIndex);
  797. };
  798. }
  799. }
  800. } else
  801. {
  802. b3Warning("No btMultiBody in the world. btRigidBody/btTypedConstraint sensor not hooked up yet");
  803. }
  804. #if 0
  805. //todo(erwincoumans) here is some sample code to hook up a force/torque sensor for btTypedConstraint/btRigidBody
  806. /*
  807. for (int i=0;i<m_data->m_dynamicsWorld->getNumConstraints();i++)
  808. {
  809. btTypedConstraint* c = m_data->m_dynamicsWorld->getConstraint(i);
  810. btJointFeedback* fb = new btJointFeedback();
  811. m_data->m_jointFeedbacks.push_back(fb);
  812. c->setJointFeedback(fb);
  813. }
  814. */
  815. #endif
  816. serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  817. hasStatus = true;
  818. break;
  819. }
  820. case CMD_SEND_DESIRED_STATE:
  821. {
  822. if (m_data->m_verboseOutput)
  823. {
  824. b3Printf("Processed CMD_SEND_DESIRED_STATE");
  825. }
  826. int bodyUniqueId = clientCmd.m_sendDesiredStateCommandArgument.m_bodyUniqueId;
  827. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  828. if (body && body->m_multiBody)
  829. {
  830. btMultiBody* mb = body->m_multiBody;
  831. btAssert(mb);
  832. switch (clientCmd.m_sendDesiredStateCommandArgument.m_controlMode)
  833. {
  834. case CONTROL_MODE_TORQUE:
  835. {
  836. if (m_data->m_verboseOutput)
  837. {
  838. b3Printf("Using CONTROL_MODE_TORQUE");
  839. }
  840. mb->clearForcesAndTorques();
  841. int torqueIndex = 0;
  842. btVector3 f(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[0],
  843. clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[1],
  844. clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[2]);
  845. btVector3 t(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[3],
  846. clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[4],
  847. clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[5]);
  848. torqueIndex+=6;
  849. mb->addBaseForce(f);
  850. mb->addBaseTorque(t);
  851. for (int link=0;link<mb->getNumLinks();link++)
  852. {
  853. for (int dof=0;dof<mb->getLink(link).m_dofCount;dof++)
  854. {
  855. double torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex];
  856. mb->addJointTorqueMultiDof(link,dof,torque);
  857. torqueIndex++;
  858. }
  859. }
  860. break;
  861. }
  862. case CONTROL_MODE_VELOCITY:
  863. {
  864. if (m_data->m_verboseOutput)
  865. {
  866. b3Printf("Using CONTROL_MODE_VELOCITY");
  867. }
  868. int numMotors = 0;
  869. //find the joint motors and apply the desired velocity and maximum force/torque
  870. {
  871. int dofIndex = 6;//skip the 3 linear + 3 angular degree of freedom entries of the base
  872. for (int link=0;link<mb->getNumLinks();link++)
  873. {
  874. if (supportsJointMotor(mb,link))
  875. {
  876. btMultiBodyJointMotor** motorPtr = m_data->m_multiBodyJointMotorMap[link];
  877. if (motorPtr)
  878. {
  879. btMultiBodyJointMotor* motor = *motorPtr;
  880. btScalar desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex];
  881. motor->setVelocityTarget(desiredVelocity);
  882. btScalar maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime;
  883. motor->setMaxAppliedImpulse(maxImp);
  884. numMotors++;
  885. }
  886. }
  887. dofIndex += mb->getLink(link).m_dofCount;
  888. }
  889. }
  890. break;
  891. }
  892. case CONTROL_MODE_POSITION_VELOCITY_PD:
  893. {
  894. if (m_data->m_verboseOutput)
  895. {
  896. b3Printf("Using CONTROL_MODE_POSITION_VELOCITY_PD");
  897. }
  898. //compute the force base on PD control
  899. mb->clearForcesAndTorques();
  900. int numMotors = 0;
  901. //find the joint motors and apply the desired velocity and maximum force/torque
  902. {
  903. int velIndex = 6;//skip the 3 linear + 3 angular degree of freedom velocity entries of the base
  904. int posIndex = 7;//skip 3 positional and 4 orientation (quaternion) positional degrees of freedom of the base
  905. for (int link=0;link<mb->getNumLinks();link++)
  906. {
  907. if (supportsJointMotor(mb,link))
  908. {
  909. btMultiBodyJointMotor** motorPtr = m_data->m_multiBodyJointMotorMap[link];
  910. if (motorPtr)
  911. {
  912. btMultiBodyJointMotor* motor = *motorPtr;
  913. btScalar desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex];
  914. btScalar desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex];
  915. btScalar kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex];
  916. btScalar kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex];
  917. int dof1 = 0;
  918. btScalar currentPosition = mb->getJointPosMultiDof(link)[dof1];
  919. btScalar currentVelocity = mb->getJointVelMultiDof(link)[dof1];
  920. btScalar positionStabiliationTerm = (desiredPosition-currentPosition)/m_data->m_physicsDeltaTime;
  921. btScalar velocityError = (desiredVelocity - currentVelocity);
  922. desiredVelocity = kp * positionStabiliationTerm +
  923. kd * velocityError;
  924. motor->setVelocityTarget(desiredVelocity);
  925. btScalar maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime;
  926. motor->setMaxAppliedImpulse(1000);//maxImp);
  927. numMotors++;
  928. }
  929. }
  930. velIndex += mb->getLink(link).m_dofCount;
  931. posIndex += mb->getLink(link).m_posVarCount;
  932. }
  933. }
  934. break;
  935. }
  936. default:
  937. {
  938. b3Warning("m_controlMode not implemented yet");
  939. break;
  940. }
  941. }
  942. }
  943. serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED;
  944. hasStatus = true;
  945. break;
  946. }
  947. case CMD_REQUEST_ACTUAL_STATE:
  948. {
  949. if (m_data->m_verboseOutput)
  950. {
  951. b3Printf("Sending the actual state (Q,U)");
  952. }
  953. int bodyUniqueId = clientCmd.m_requestActualStateInformationCommandArgument.m_bodyUniqueId;
  954. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  955. if (body && body->m_multiBody)
  956. {
  957. btMultiBody* mb = body->m_multiBody;
  958. SharedMemoryStatus& serverCmd = serverStatusOut;
  959. serverStatusOut.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
  960. serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
  961. int totalDegreeOfFreedomQ = 0;
  962. int totalDegreeOfFreedomU = 0;
  963. //always add the base, even for static (non-moving objects)
  964. //so that we can easily move the 'fixed' base when needed
  965. //do we don't use this conditional "if (!mb->hasFixedBase())"
  966. {
  967. btTransform tr;
  968. tr.setOrigin(mb->getBasePos());
  969. tr.setRotation(mb->getWorldToBaseRot().inverse());
  970. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[0] =
  971. body->m_rootLocalInertialFrame.getOrigin()[0];
  972. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[1] =
  973. body->m_rootLocalInertialFrame.getOrigin()[1];
  974. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[2] =
  975. body->m_rootLocalInertialFrame.getOrigin()[2];
  976. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[3] =
  977. body->m_rootLocalInertialFrame.getRotation()[0];
  978. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[4] =
  979. body->m_rootLocalInertialFrame.getRotation()[1];
  980. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[5] =
  981. body->m_rootLocalInertialFrame.getRotation()[2];
  982. serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[6] =
  983. body->m_rootLocalInertialFrame.getRotation()[3];
  984. //base position in world space, carthesian
  985. serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
  986. serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1];
  987. serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2];
  988. //base orientation, quaternion x,y,z,w, in world space, carthesian
  989. serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0];
  990. serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1];
  991. serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2];
  992. serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3];
  993. totalDegreeOfFreedomQ +=7;//pos + quaternion
  994. //base linear velocity (in world space, carthesian)
  995. serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = mb->getBaseVel()[0];
  996. serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = mb->getBaseVel()[1];
  997. serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = mb->getBaseVel()[2];
  998. //base angular velocity (in world space, carthesian)
  999. serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = mb->getBaseOmega()[0];
  1000. serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = mb->getBaseOmega()[1];
  1001. serverCmd.m_sendActualStateArgs.m_actualStateQdot[5] = mb->getBaseOmega()[2];
  1002. totalDegreeOfFreedomU += 6;//3 linear and 3 angular DOF
  1003. }
  1004. for (int l=0;l<mb->getNumLinks();l++)
  1005. {
  1006. for (int d=0;d<mb->getLink(l).m_posVarCount;d++)
  1007. {
  1008. serverCmd.m_sendActualStateArgs.m_actualStateQ[totalDegreeOfFreedomQ++] = mb->getJointPosMultiDof(l)[d];
  1009. }
  1010. for (int d=0;d<mb->getLink(l).m_dofCount;d++)
  1011. {
  1012. serverCmd.m_sendActualStateArgs.m_actualStateQdot[totalDegreeOfFreedomU++] = mb->getJointVelMultiDof(l)[d];
  1013. }
  1014. if (0 == mb->getLink(l).m_jointFeedback)
  1015. {
  1016. for (int d=0;d<6;d++)
  1017. {
  1018. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+d]=0;
  1019. }
  1020. } else
  1021. {
  1022. btVector3 sensedForce = mb->getLink(l).m_jointFeedback->m_reactionForces.getLinear();
  1023. btVector3 sensedTorque = mb->getLink(l).m_jointFeedback->m_reactionForces.getAngular();
  1024. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+0] = sensedForce[0];
  1025. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+1] = sensedForce[1];
  1026. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+2] = sensedForce[2];
  1027. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+3] = sensedTorque[0];
  1028. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+4] = sensedTorque[1];
  1029. serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+5] = sensedTorque[2];
  1030. }
  1031. }
  1032. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ;
  1033. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU;
  1034. hasStatus = true;
  1035. } else
  1036. {
  1037. if (body && body->m_rigidBody)
  1038. {
  1039. btRigidBody* rb = body->m_rigidBody;
  1040. SharedMemoryStatus& serverCmd = serverStatusOut;
  1041. serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
  1042. serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
  1043. int totalDegreeOfFreedomQ = 0;
  1044. int totalDegreeOfFreedomU = 0;
  1045. btTransform tr = rb->getWorldTransform();
  1046. //base position in world space, carthesian
  1047. serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
  1048. serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1];
  1049. serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2];
  1050. //base orientation, quaternion x,y,z,w, in world space, carthesian
  1051. serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0];
  1052. serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1];
  1053. serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2];
  1054. serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3];
  1055. totalDegreeOfFreedomQ +=7;//pos + quaternion
  1056. //base linear velocity (in world space, carthesian)
  1057. serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = rb->getLinearVelocity()[0];
  1058. serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = rb->getLinearVelocity()[1];
  1059. serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = rb->getLinearVelocity()[2];
  1060. //base angular velocity (in world space, carthesian)
  1061. serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = rb->getAngularVelocity()[0];
  1062. serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = rb->getAngularVelocity()[1];
  1063. serverCmd.m_sendActualStateArgs.m_actualStateQdot[5] = rb->getAngularVelocity()[2];
  1064. totalDegreeOfFreedomU += 6;//3 linear and 3 angular DOF
  1065. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ;
  1066. serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU;
  1067. hasStatus = true;
  1068. } else
  1069. {
  1070. b3Warning("Request state but no multibody or rigid body available");
  1071. SharedMemoryStatus& serverCmd = serverStatusOut;
  1072. serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_FAILED;
  1073. hasStatus = true;
  1074. }
  1075. }
  1076. break;
  1077. }
  1078. case CMD_STEP_FORWARD_SIMULATION:
  1079. {
  1080. if (m_data->m_verboseOutput)
  1081. {
  1082. b3Printf("Step simulation request");
  1083. }
  1084. m_data->m_dynamicsWorld->stepSimulation(m_data->m_physicsDeltaTime,0);
  1085. SharedMemoryStatus& serverCmd =serverStatusOut;
  1086. serverCmd.m_type = CMD_STEP_FORWARD_SIMULATION_COMPLETED;
  1087. hasStatus = true;
  1088. break;
  1089. }
  1090. case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
  1091. {
  1092. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME)
  1093. {
  1094. m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime;
  1095. }
  1096. if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY)
  1097. {
  1098. btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0],
  1099. clientCmd.m_physSimParamArgs.m_gravityAcceleration[1],
  1100. clientCmd.m_physSimParamArgs.m_gravityAcceleration[2]);
  1101. this->m_data->m_dynamicsWorld->setGravity(grav);
  1102. if (m_data->m_verboseOutput)
  1103. {
  1104. b3Printf("Updated Gravity: %f,%f,%f",grav[0],grav[1],grav[2]);
  1105. }
  1106. }
  1107. SharedMemoryStatus& serverCmd =serverStatusOut;
  1108. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1109. hasStatus = true;
  1110. break;
  1111. };
  1112. case CMD_INIT_POSE:
  1113. {
  1114. if (m_data->m_verboseOutput)
  1115. {
  1116. b3Printf("Server Init Pose not implemented yet");
  1117. }
  1118. int bodyUniqueId = clientCmd.m_initPoseArgs.m_bodyUniqueId;
  1119. InteralBodyData* body = m_data->getHandle(bodyUniqueId);
  1120. if (body && body->m_multiBody)
  1121. {
  1122. btMultiBody* mb = body->m_multiBody;
  1123. if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION)
  1124. {
  1125. btVector3 zero(0,0,0);
  1126. mb->setBaseVel(zero);
  1127. mb->setBasePos(btVector3(
  1128. clientCmd.m_initPoseArgs.m_initialStateQ[0],
  1129. clientCmd.m_initPoseArgs.m_initialStateQ[1],
  1130. clientCmd.m_initPoseArgs.m_initialStateQ[2]));
  1131. }
  1132. if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION)
  1133. {
  1134. mb->setBaseOmega(btVector3(0,0,0));
  1135. mb->setWorldToBaseRot(btQuaternion(
  1136. clientCmd.m_initPoseArgs.m_initialStateQ[3],
  1137. clientCmd.m_initPoseArgs.m_initialStateQ[4],
  1138. clientCmd.m_initPoseArgs.m_initialStateQ[5],
  1139. clientCmd.m_initPoseArgs.m_initialStateQ[6]));
  1140. }
  1141. if (clientCmd.m_updateFlags & INIT_POSE_HAS_JOINT_STATE)
  1142. {
  1143. int dofIndex = 7;
  1144. for (int i=0;i<mb->getNumLinks();i++)
  1145. {
  1146. if (mb->getLink(i).m_dofCount==1)
  1147. {
  1148. mb->setJointPos(i,clientCmd.m_initPoseArgs.m_initialStateQ[dofIndex]);
  1149. mb->setJointVel(i,0);
  1150. }
  1151. dofIndex += mb->getLink(i).m_dofCount;
  1152. }
  1153. }
  1154. }
  1155. SharedMemoryStatus& serverCmd =serverStatusOut;
  1156. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1157. hasStatus = true;
  1158. break;
  1159. }
  1160. case CMD_RESET_SIMULATION:
  1161. {
  1162. //clean up all data
  1163. if (m_data && m_data->m_guiHelper && m_data->m_guiHelper->getRenderInterface())
  1164. {
  1165. m_data->m_guiHelper->getRenderInterface()->removeAllInstances();
  1166. }
  1167. deleteDynamicsWorld();
  1168. createEmptyDynamicsWorld();
  1169. m_data->exitHandles();
  1170. m_data->initHandles();
  1171. SharedMemoryStatus& serverCmd =serverStatusOut;
  1172. serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED;
  1173. hasStatus = true;
  1174. break;
  1175. }
  1176. case CMD_CREATE_RIGID_BODY:
  1177. case CMD_CREATE_BOX_COLLISION_SHAPE:
  1178. {
  1179. btVector3 halfExtents(1,1,1);
  1180. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_HALF_EXTENTS)
  1181. {
  1182. halfExtents = btVector3(
  1183. clientCmd.m_createBoxShapeArguments.m_halfExtentsX,
  1184. clientCmd.m_createBoxShapeArguments.m_halfExtentsY,
  1185. clientCmd.m_createBoxShapeArguments.m_halfExtentsZ);
  1186. }
  1187. btTransform startTrans;
  1188. startTrans.setIdentity();
  1189. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_POSITION)
  1190. {
  1191. startTrans.setOrigin(btVector3(
  1192. clientCmd.m_createBoxShapeArguments.m_initialPosition[0],
  1193. clientCmd.m_createBoxShapeArguments.m_initialPosition[1],
  1194. clientCmd.m_createBoxShapeArguments.m_initialPosition[2]));
  1195. }
  1196. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_ORIENTATION)
  1197. {
  1198. startTrans.setRotation(btQuaternion(
  1199. clientCmd.m_createBoxShapeArguments.m_initialOrientation[0],
  1200. clientCmd.m_createBoxShapeArguments.m_initialOrientation[1],
  1201. clientCmd.m_createBoxShapeArguments.m_initialOrientation[2],
  1202. clientCmd.m_createBoxShapeArguments.m_initialOrientation[3]));
  1203. }
  1204. btScalar mass = 0.f;
  1205. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_MASS)
  1206. {
  1207. mass = clientCmd.m_createBoxShapeArguments.m_mass;
  1208. }
  1209. int shapeType = COLLISION_SHAPE_TYPE_BOX;
  1210. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE)
  1211. {
  1212. shapeType = clientCmd.m_createBoxShapeArguments.m_collisionShapeType;
  1213. }
  1214. btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
  1215. m_data->m_worldImporters.push_back(worldImporter);
  1216. btCollisionShape* shape = 0;
  1217. switch (shapeType)
  1218. {
  1219. case COLLISION_SHAPE_TYPE_CYLINDER_X:
  1220. {
  1221. btScalar radius = halfExtents[1];
  1222. btScalar height = halfExtents[0];
  1223. shape = worldImporter->createCylinderShapeX(radius,height);
  1224. break;
  1225. }
  1226. case COLLISION_SHAPE_TYPE_CYLINDER_Y:
  1227. {
  1228. btScalar radius = halfExtents[0];
  1229. btScalar height = halfExtents[1];
  1230. shape = worldImporter->createCylinderShapeY(radius,height);
  1231. break;
  1232. }
  1233. case COLLISION_SHAPE_TYPE_CYLINDER_Z:
  1234. {
  1235. btScalar radius = halfExtents[1];
  1236. btScalar height = halfExtents[2];
  1237. shape = worldImporter->createCylinderShapeZ(radius,height);
  1238. break;
  1239. }
  1240. case COLLISION_SHAPE_TYPE_CAPSULE_X:
  1241. {
  1242. btScalar radius = halfExtents[1];
  1243. btScalar height = halfExtents[0];
  1244. shape = worldImporter->createCapsuleShapeX(radius,height);
  1245. break;
  1246. }
  1247. case COLLISION_SHAPE_TYPE_CAPSULE_Y:
  1248. {
  1249. btScalar radius = halfExtents[0];
  1250. btScalar height = halfExtents[1];
  1251. shape = worldImporter->createCapsuleShapeY(radius,height);
  1252. break;
  1253. }
  1254. case COLLISION_SHAPE_TYPE_CAPSULE_Z:
  1255. {
  1256. btScalar radius = halfExtents[1];
  1257. btScalar height = halfExtents[2];
  1258. shape = worldImporter->createCapsuleShapeZ(radius,height);
  1259. break;
  1260. }
  1261. case COLLISION_SHAPE_TYPE_SPHERE:
  1262. {
  1263. btScalar radius = halfExtents[0];
  1264. shape = worldImporter->createSphereShape(radius);
  1265. break;
  1266. }
  1267. case COLLISION_SHAPE_TYPE_BOX:
  1268. default:
  1269. {
  1270. shape = worldImporter->createBoxShape(halfExtents);
  1271. }
  1272. }
  1273. bool isDynamic = (mass>0);
  1274. btRigidBody* rb = worldImporter->createRigidBody(isDynamic,mass,startTrans,shape,0);
  1275. rb->setRollingFriction(0.2);
  1276. //m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
  1277. btVector4 colorRGBA(1,0,0,1);
  1278. if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLOR)
  1279. {
  1280. colorRGBA[0] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[0];
  1281. colorRGBA[1] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[1];
  1282. colorRGBA[2] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[2];
  1283. colorRGBA[3] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[3];
  1284. }
  1285. m_data->m_guiHelper->createCollisionShapeGraphicsObject(rb->getCollisionShape());
  1286. m_data->m_guiHelper->createCollisionObjectGraphicsObject(rb,colorRGBA);
  1287. SharedMemoryStatus& serverCmd =serverStatusOut;
  1288. serverCmd.m_type = CMD_RIGID_BODY_CREATION_COMPLETED;
  1289. int bodyUniqueId = m_data->allocHandle();
  1290. InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
  1291. serverCmd.m_rigidBodyCreateArgs.m_bodyUniqueId = bodyUniqueId;
  1292. bodyHandle->m_rootLocalInertialFrame.setIdentity();
  1293. bodyHandle->m_rigidBody = rb;
  1294. hasStatus = true;
  1295. break;
  1296. }
  1297. case CMD_PICK_BODY:
  1298. {
  1299. pickBody(btVector3(clientCmd.m_pickBodyArguments.m_rayFromWorld[0],
  1300. clientCmd.m_pickBodyArguments.m_rayFromWorld[1],
  1301. clientCmd.m_pickBodyArguments.m_rayFromWorld[2]),
  1302. btVector3(clientCmd.m_pickBodyArguments.m_rayToWorld[0],
  1303. clientCmd.m_pickBodyArguments.m_rayToWorld[1],
  1304. clientCmd.m_pickBodyArguments.m_rayToWorld[2]));
  1305. SharedMemoryStatus& serverCmd =serverStatusOut;
  1306. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1307. hasStatus = true;
  1308. break;
  1309. }
  1310. case CMD_MOVE_PICKED_BODY:
  1311. {
  1312. movePickedBody(btVector3(clientCmd.m_pickBodyArguments.m_rayFromWorld[0],
  1313. clientCmd.m_pickBodyArguments.m_rayFromWorld[1],
  1314. clientCmd.m_pickBodyArguments.m_rayFromWorld[2]),
  1315. btVector3(clientCmd.m_pickBodyArguments.m_rayToWorld[0],
  1316. clientCmd.m_pickBodyArguments.m_rayToWorld[1],
  1317. clientCmd.m_pickBodyArguments.m_rayToWorld[2]));
  1318. SharedMemoryStatus& serverCmd =serverStatusOut;
  1319. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1320. hasStatus = true;
  1321. break;
  1322. }
  1323. case CMD_REMOVE_PICKING_CONSTRAINT_BODY:
  1324. {
  1325. removePickingConstraint();
  1326. SharedMemoryStatus& serverCmd =serverStatusOut;
  1327. serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
  1328. hasStatus = true;
  1329. break;
  1330. }
  1331. default:
  1332. {
  1333. b3Error("Unknown command encountered");
  1334. SharedMemoryStatus& serverCmd =serverStatusOut;
  1335. serverCmd.m_type = CMD_UNKNOWN_COMMAND_FLUSHED;
  1336. hasStatus = true;
  1337. }
  1338. };
  1339. }
  1340. }
  1341. return hasStatus;
  1342. }
  1343. void PhysicsServerCommandProcessor::renderScene()
  1344. {
  1345. if (m_data->m_guiHelper)
  1346. {
  1347. m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld);
  1348. m_data->m_guiHelper->render(m_data->m_dynamicsWorld);
  1349. }
  1350. }
  1351. void PhysicsServerCommandProcessor::physicsDebugDraw(int debugDrawFlags)
  1352. {
  1353. if (m_data->m_dynamicsWorld)
  1354. {
  1355. if (m_data->m_dynamicsWorld->getDebugDrawer())
  1356. {
  1357. m_data->m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugDrawFlags);
  1358. m_data->m_dynamicsWorld->debugDrawWorld();
  1359. }
  1360. }
  1361. }
  1362. bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
  1363. {
  1364. if (m_data->m_dynamicsWorld==0)
  1365. return false;
  1366. btCollisionWorld::ClosestRayResultCallback rayCallback(rayFromWorld, rayToWorld);
  1367. m_data->m_dynamicsWorld->rayTest(rayFromWorld, rayToWorld, rayCallback);
  1368. if (rayCallback.hasHit())
  1369. {
  1370. btVector3 pickPos = rayCallback.m_hitPointWorld;
  1371. btRigidBody* body = (btRigidBody*)btRigidBody::upcast(rayCallback.m_collisionObject);
  1372. if (body)
  1373. {
  1374. //other exclusions?
  1375. if (!(body->isStaticObject() || body->isKinematicObject()))
  1376. {
  1377. m_data->m_pickedBody = body;
  1378. m_data->m_pickedBody->setActivationState(DISABLE_DEACTIVATION);
  1379. //printf("pickPos=%f,%f,%f\n",pickPos.getX(),pickPos.getY(),pickPos.getZ());
  1380. btVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos;
  1381. btPoint2PointConstraint* p2p = new btPoint2PointConstraint(*body, localPivot);
  1382. m_data->m_dynamicsWorld->addConstraint(p2p, true);
  1383. m_data->m_pickedConstraint = p2p;
  1384. btScalar mousePickClamping = 30.f;
  1385. p2p->m_setting.m_impulseClamp = mousePickClamping;
  1386. //very weak constraint for picking
  1387. p2p->m_setting.m_tau = 0.001f;
  1388. }
  1389. } else
  1390. {
  1391. btMultiBodyLinkCollider* multiCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(rayCallback.m_collisionObject);
  1392. if (multiCol && multiCol->m_multiBody)
  1393. {
  1394. m_data->m_prevCanSleep = multiCol->m_multiBody->getCanSleep();
  1395. multiCol->m_multiBody->setCanSleep(false);
  1396. btVector3 pivotInA = multiCol->m_multiBody->worldPosToLocal(multiCol->m_link, pickPos);
  1397. btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(multiCol->m_multiBody,multiCol->m_link,0,pivotInA,pickPos);
  1398. //if you add too much energy to the system, causing high angular velocities, simulation 'explodes'
  1399. //see also http://www.bulletphysics.org/Bullet/phpBB3/viewtopic.php?f=4&t=949
  1400. //so we try to avoid it by clamping the maximum impulse (force) that the mouse pick can apply
  1401. //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?)
  1402. btScalar scaling=1;
  1403. p2p->setMaxAppliedImpulse(2*scaling);
  1404. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  1405. world->addMultiBodyConstraint(p2p);
  1406. m_data->m_pickingMultiBodyPoint2Point =p2p;
  1407. }
  1408. }
  1409. // pickObject(pickPos, rayCallback.m_collisionObject);
  1410. m_data->m_oldPickingPos = rayToWorld;
  1411. m_data->m_hitPos = pickPos;
  1412. m_data->m_oldPickingDist = (pickPos - rayFromWorld).length();
  1413. // printf("hit !\n");
  1414. //add p2p
  1415. }
  1416. return false;
  1417. }
  1418. bool PhysicsServerCommandProcessor::movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
  1419. {
  1420. if (m_data->m_pickedBody && m_data->m_pickedConstraint)
  1421. {
  1422. btPoint2PointConstraint* pickCon = static_cast<btPoint2PointConstraint*>(m_data->m_pickedConstraint);
  1423. if (pickCon)
  1424. {
  1425. //keep it at the same picking distance
  1426. btVector3 dir = rayToWorld-rayFromWorld;
  1427. dir.normalize();
  1428. dir *= m_data->m_oldPickingDist;
  1429. btVector3 newPivotB = rayFromWorld + dir;
  1430. pickCon->setPivotB(newPivotB);
  1431. }
  1432. }
  1433. if (m_data->m_pickingMultiBodyPoint2Point)
  1434. {
  1435. //keep it at the same picking distance
  1436. btVector3 dir = rayToWorld-rayFromWorld;
  1437. dir.normalize();
  1438. dir *= m_data->m_oldPickingDist;
  1439. btVector3 newPivotB = rayFromWorld + dir;
  1440. m_data->m_pickingMultiBodyPoint2Point->setPivotInB(newPivotB);
  1441. }
  1442. return false;
  1443. }
  1444. void PhysicsServerCommandProcessor::removePickingConstraint()
  1445. {
  1446. if (m_data->m_pickedConstraint)
  1447. {
  1448. m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint);
  1449. delete m_data->m_pickedConstraint;
  1450. m_data->m_pickedConstraint = 0;
  1451. m_data->m_pickedBody = 0;
  1452. }
  1453. if (m_data->m_pickingMultiBodyPoint2Point)
  1454. {
  1455. m_data->m_pickingMultiBodyPoint2Point->getMultiBodyA()->setCanSleep(m_data->m_prevCanSleep);
  1456. btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
  1457. world->removeMultiBodyConstraint(m_data->m_pickingMultiBodyPoint2Point);
  1458. delete m_data->m_pickingMultiBodyPoint2Point;
  1459. m_data->m_pickingMultiBodyPoint2Point = 0;
  1460. }
  1461. }
  1462. void PhysicsServerCommandProcessor::enableCommandLogging(bool enable, const char* fileName)
  1463. {
  1464. if (enable)
  1465. {
  1466. if (0==m_data->m_commandLogger)
  1467. {
  1468. m_data->m_commandLogger = new CommandLogger(fileName);
  1469. }
  1470. } else
  1471. {
  1472. if (0!=m_data->m_commandLogger)
  1473. {
  1474. delete m_data->m_commandLogger;
  1475. m_data->m_commandLogger = 0;
  1476. }
  1477. }
  1478. }
  1479. void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
  1480. {
  1481. CommandLogPlayback* pb = new CommandLogPlayback(fileName);
  1482. m_data->m_logPlayback = pb;
  1483. }