12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176317731783179318031813182318331843185318631873188318931903191319231933194319531963197319831993200320132023203320432053206320732083209321032113212321332143215321632173218321932203221322232233224322532263227322832293230323132323233323432353236323732383239324032413242324332443245324632473248324932503251325232533254325532563257325832593260326132623263326432653266326732683269327032713272327332743275327632773278327932803281328232833284328532863287328832893290329132923293329432953296329732983299330033013302330333043305330633073308330933103311331233133314331533163317331833193320332133223323332433253326332733283329333033313332333333343335333633373338333933403341334233433344334533463347334833493350335133523353335433553356335733583359336033613362336333643365336633673368336933703371337233733374337533763377337833793380338133823383338433853386338733883389339033913392339333943395339633973398339934003401340234033404340534063407340834093410341134123413341434153416341734183419342034213422342334243425342634273428342934303431343234333434343534363437343834393440344134423443344434453446344734483449345034513452345334543455345634573458345934603461346234633464346534663467346834693470347134723473347434753476347734783479348034813482348334843485348634873488348934903491349234933494349534963497349834993500350135023503350435053506350735083509351035113512351335143515351635173518351935203521352235233524352535263527352835293530353135323533353435353536353735383539354035413542354335443545354635473548354935503551355235533554355535563557355835593560356135623563356435653566356735683569357035713572357335743575357635773578357935803581358235833584358535863587358835893590359135923593359435953596359735983599360036013602360336043605360636073608360936103611361236133614361536163617361836193620362136223623362436253626362736283629363036313632363336343635363636373638363936403641 |
- #include "PhysicsServerCommandProcessor.h"
- #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
- #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
- #include "../Importers/ImportURDFDemo/URDF2Bullet.h"
- #include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
- #include "TinyRendererVisualShapeConverter.h"
- #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
- #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
- #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
- #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
- #include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h"
- #include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
- #include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
- #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
- #include "LinearMath/btHashMap.h"
- #include "BulletInverseDynamics/MultiBodyTree.hpp"
- #include "IKTrajectoryHelper.h"
- #include "btBulletDynamicsCommon.h"
- #include "LinearMath/btTransform.h"
- #include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
- #include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
- #include "LinearMath/btSerializer.h"
- #include "Bullet3Common/b3Logging.h"
- #include "../CommonInterfaces/CommonGUIHelperInterface.h"
- #include "SharedMemoryCommands.h"
- //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
- btVector3 gLastPickPos(0, 0, 0);
- bool gCloseToKuka=false;
- bool gEnableRealTimeSimVR=false;
- bool gCreateSamuraiRobotAssets = true;
- int gCreateObjectSimVR = -1;
- btScalar simTimeScalingFactor = 1;
- btScalar gRhsClamp = 1.f;
- struct UrdfLinkNameMapUtil
- {
- btMultiBody* m_mb;
- btDefaultSerializer* m_memSerializer;
- UrdfLinkNameMapUtil():m_mb(0),m_memSerializer(0)
- {
- }
- virtual ~UrdfLinkNameMapUtil()
- {
- delete m_memSerializer;
- }
- };
- struct SharedMemoryDebugDrawer : public btIDebugDraw
- {
- int m_debugMode;
- btAlignedObjectArray<SharedMemLines> m_lines2;
- SharedMemoryDebugDrawer ()
- :m_debugMode(0)
- {
- }
- virtual void drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color)
- {
- }
- virtual void reportErrorWarning(const char* warningString)
- {
- }
- virtual void draw3dText(const btVector3& location,const char* textString)
- {
- }
- virtual void setDebugMode(int debugMode)
- {
- m_debugMode = debugMode;
- }
- virtual int getDebugMode() const
- {
- return m_debugMode;
- }
- virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color)
- {
- SharedMemLines line;
- line.m_from = from;
- line.m_to = to;
- line.m_color = color;
- m_lines2.push_back(line);
- }
- };
- struct InteralBodyData
- {
- btMultiBody* m_multiBody;
- btRigidBody* m_rigidBody;
- int m_testData;
- btTransform m_rootLocalInertialFrame;
- btAlignedObjectArray<btTransform> m_linkLocalInertialFrames;
- InteralBodyData()
- :m_multiBody(0),
- m_rigidBody(0),
- m_testData(0)
- {
- m_rootLocalInertialFrame.setIdentity();
- }
- };
- ///todo: templatize this
- struct InternalBodyHandle : public InteralBodyData
- {
- BT_DECLARE_ALIGNED_ALLOCATOR();
- int m_nextFreeHandle;
- void SetNextFree(int next)
- {
- m_nextFreeHandle = next;
- }
- int GetNextFree() const
- {
- return m_nextFreeHandle;
- }
- };
- class btCommandChunk
- {
- public:
- int m_chunkCode;
- int m_length;
- void *m_oldPtr;
- int m_dna_nr;
- int m_number;
- };
- class bCommandChunkPtr4
- {
- public:
- bCommandChunkPtr4(){}
- int code;
- int len;
- union
- {
- int m_uniqueInt;
- };
- int dna_nr;
- int nr;
- };
- // ----------------------------------------------------- //
- class bCommandChunkPtr8
- {
- public:
- bCommandChunkPtr8(){}
- int code, len;
- union
- {
- int m_uniqueInts[2];
- };
- int dna_nr, nr;
- };
- struct CommandLogger
- {
- FILE* m_file;
- void writeHeader(unsigned char* buffer) const
- {
- #ifdef BT_USE_DOUBLE_PRECISION
- memcpy(buffer, "BT3CMDd", 7);
- #else
- memcpy(buffer, "BT3CMDf", 7);
- #endif //BT_USE_DOUBLE_PRECISION
- int littleEndian= 1;
- littleEndian= ((char*)&littleEndian)[0];
- if (sizeof(void*)==8)
- {
- buffer[7] = '-';
- } else
- {
- buffer[7] = '_';
- }
- if (littleEndian)
- {
- buffer[8]='v';
- } else
- {
- buffer[8]='V';
- }
- buffer[9] = 0;
- buffer[10] = 0;
- buffer[11] = 0;
- int ver = btGetVersion();
- if (ver>=0 && ver<999)
- {
- sprintf((char*)&buffer[9],"%d",ver);
- }
- }
- void logCommand(const SharedMemoryCommand& command)
- {
- btCommandChunk chunk;
- chunk.m_chunkCode = command.m_type;
- chunk.m_oldPtr = 0;
- chunk.m_dna_nr = 0;
- chunk.m_length = sizeof(SharedMemoryCommand);
- chunk.m_number = 1;
- fwrite((const char*)&chunk,sizeof(btCommandChunk), 1,m_file);
- fwrite((const char*)&command,sizeof(SharedMemoryCommand),1,m_file);
- }
- CommandLogger(const char* fileName)
- {
- m_file = fopen(fileName,"wb");
- unsigned char buf[15];
- buf[12] = 12;
- buf[13] = 13;
- buf[14] = 14;
- writeHeader(buf);
- fwrite(buf,12,1,m_file);
- }
- virtual ~CommandLogger()
- {
- fclose(m_file);
- }
- };
- struct CommandLogPlayback
- {
- unsigned char m_header[12];
- FILE* m_file;
- bool m_bitsVary;
- bool m_fileIs64bit;
- CommandLogPlayback(const char* fileName)
- {
- m_file = fopen(fileName,"rb");
- if (m_file)
- {
- fread(m_header,12,1,m_file);
- }
- unsigned char c = m_header[7];
- m_fileIs64bit = (c=='-');
- const bool VOID_IS_8 = ((sizeof(void*)==8));
- m_bitsVary = (VOID_IS_8 != m_fileIs64bit);
- }
- virtual ~CommandLogPlayback()
- {
- if (m_file)
- {
- fclose(m_file);
- m_file=0;
- }
- }
- bool processNextCommand(SharedMemoryCommand* cmd)
- {
- if (m_file)
- {
- size_t s = 0;
- if (m_fileIs64bit)
- {
- bCommandChunkPtr8 chunk8;
- s = fread((void*)&chunk8,sizeof(bCommandChunkPtr8),1,m_file);
- } else
- {
- bCommandChunkPtr4 chunk4;
- s = fread((void*)&chunk4,sizeof(bCommandChunkPtr4),1,m_file);
- }
- if (s==1)
- {
- s = fread(cmd,sizeof(SharedMemoryCommand),1,m_file);
- return (s==1);
- }
- }
- return false;
- }
- };
- struct SaveWorldObjectData
- {
- b3AlignedObjectArray<int> m_bodyUniqueIds;
- std::string m_fileName;
- };
- struct PhysicsServerCommandProcessorInternalData
- {
- ///handle management
- btAlignedObjectArray<InternalBodyHandle> m_bodyHandles;
- int m_numUsedHandles; // number of active handles
- int m_firstFreeHandle; // free handles list
- InternalBodyHandle* getHandle(int handle)
- {
- btAssert(handle>=0);
- btAssert(handle<m_bodyHandles.size());
- if ((handle<0) || (handle>=m_bodyHandles.size()))
- {
- return 0;
- }
- return &m_bodyHandles[handle];
- }
- const InternalBodyHandle* getHandle(int handle) const
- {
- return &m_bodyHandles[handle];
- }
- void increaseHandleCapacity(int extraCapacity)
- {
- int curCapacity = m_bodyHandles.size();
- btAssert(curCapacity == m_numUsedHandles);
- int newCapacity = curCapacity + extraCapacity;
- m_bodyHandles.resize(newCapacity);
- {
- for (int i = curCapacity; i < newCapacity; i++)
- m_bodyHandles[i].SetNextFree(i + 1);
- m_bodyHandles[newCapacity - 1].SetNextFree(-1);
- }
- m_firstFreeHandle = curCapacity;
- }
- void initHandles()
- {
- m_numUsedHandles = 0;
- m_firstFreeHandle = -1;
- increaseHandleCapacity(1);
- }
- void exitHandles()
- {
- m_bodyHandles.resize(0);
- m_firstFreeHandle = -1;
- m_numUsedHandles = 0;
- }
- int allocHandle()
- {
- btAssert(m_firstFreeHandle>=0);
- int handle = m_firstFreeHandle;
- m_firstFreeHandle = getHandle(handle)->GetNextFree();
- m_numUsedHandles++;
- if (m_firstFreeHandle<0)
- {
- int curCapacity = m_bodyHandles.size();
- int additionalCapacity= m_bodyHandles.size();
- increaseHandleCapacity(additionalCapacity);
- getHandle(handle)->SetNextFree(m_firstFreeHandle);
- }
- return handle;
- }
- void freeHandle(int handle)
- {
- btAssert(handle >= 0);
- getHandle(handle)->SetNextFree(m_firstFreeHandle);
- m_firstFreeHandle = handle;
- m_numUsedHandles--;
- }
- ///end handle management
- bool m_allowRealTimeSimulation;
- bool m_hasGround;
- btMultiBodyFixedConstraint* m_gripperRigidbodyFixed;
- btMultiBody* m_gripperMultiBody;
- btMultiBodyFixedConstraint* m_kukaGripperFixed;
- btMultiBody* m_kukaGripperMultiBody;
- btMultiBodyPoint2Point* m_kukaGripperRevolute1;
- btMultiBodyPoint2Point* m_kukaGripperRevolute2;
-
- int m_huskyId;
- int m_KukaId;
- int m_sphereId;
- int m_gripperId;
- CommandLogger* m_commandLogger;
- CommandLogPlayback* m_logPlayback;
- btScalar m_physicsDeltaTime;
- btScalar m_numSimulationSubSteps;
- btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks;
- btHashMap<btHashPtr, btInverseDynamics::MultiBodyTree*> m_inverseDynamicsBodies;
- btHashMap<btHashPtr, IKTrajectoryHelper*> m_inverseKinematicsHelpers;
- b3AlignedObjectArray<SaveWorldObjectData> m_saveWorldBodyData;
- btAlignedObjectArray<btBulletWorldImporter*> m_worldImporters;
- btAlignedObjectArray<UrdfLinkNameMapUtil*> m_urdfLinkNameMapper;
- btAlignedObjectArray<std::string*> m_strings;
- btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
- btBroadphaseInterface* m_broadphase;
- btCollisionDispatcher* m_dispatcher;
- btMultiBodyConstraintSolver* m_solver;
- btDefaultCollisionConfiguration* m_collisionConfiguration;
- btMultiBodyDynamicsWorld* m_dynamicsWorld;
- SharedMemoryDebugDrawer* m_remoteDebugDrawer;
-
- btAlignedObjectArray<b3ContactPointData> m_cachedContactPoints;
- btAlignedObjectArray<int> m_sdfRecentLoadedBodies;
- struct GUIHelperInterface* m_guiHelper;
- int m_sharedMemoryKey;
- bool m_verboseOutput;
- //data for picking objects
- class btRigidBody* m_pickedBody;
- class btTypedConstraint* m_pickedConstraint;
- class btMultiBodyPoint2Point* m_pickingMultiBodyPoint2Point;
- btVector3 m_oldPickingPos;
- btVector3 m_hitPos;
- btScalar m_oldPickingDist;
- bool m_prevCanSleep;
- TinyRendererVisualShapeConverter m_visualConverter;
- PhysicsServerCommandProcessorInternalData()
- :m_hasGround(false),
- m_gripperRigidbodyFixed(0),
- m_gripperMultiBody(0),
- m_kukaGripperFixed(0),
- m_kukaGripperMultiBody(0),
- m_kukaGripperRevolute1(0),
- m_kukaGripperRevolute2(0),
- m_allowRealTimeSimulation(false),
- m_huskyId(-1),
- m_KukaId(-1),
- m_sphereId(-1),
- m_gripperId(-1),
- m_commandLogger(0),
- m_logPlayback(0),
- m_physicsDeltaTime(1./240.),
- m_numSimulationSubSteps(0),
- m_dynamicsWorld(0),
- m_remoteDebugDrawer(0),
- m_guiHelper(0),
- m_sharedMemoryKey(SHARED_MEMORY_KEY),
- m_verboseOutput(false),
- m_pickedBody(0),
- m_pickedConstraint(0),
- m_pickingMultiBodyPoint2Point(0)
- {
- initHandles();
- #if 0
- btAlignedObjectArray<int> bla;
- for (int i=0;i<1024;i++)
- {
- int handle = allocHandle();
- bla.push_back(handle);
- InternalBodyHandle* body = getHandle(handle);
- InteralBodyData* body2 = body;
- }
- for (int i=0;i<bla.size();i++)
- {
- freeHandle(bla[i]);
- }
- bla.resize(0);
- for (int i=0;i<1024;i++)
- {
- int handle = allocHandle();
- bla.push_back(handle);
- InternalBodyHandle* body = getHandle(handle);
- InteralBodyData* body2 = body;
- }
- for (int i=0;i<bla.size();i++)
- {
- freeHandle(bla[i]);
- }
- bla.resize(0);
- for (int i=0;i<1024;i++)
- {
- int handle = allocHandle();
- bla.push_back(handle);
- InternalBodyHandle* body = getHandle(handle);
- InteralBodyData* body2 = body;
- }
- for (int i=0;i<bla.size();i++)
- {
- freeHandle(bla[i]);
- }
- #endif
- }
- btInverseDynamics::MultiBodyTree* findOrCreateTree(btMultiBody* multiBody)
- {
- btInverseDynamics::MultiBodyTree* tree = 0;
-
- btInverseDynamics::MultiBodyTree** treePtrPtr =
- m_inverseDynamicsBodies.find(multiBody);
-
- if (treePtrPtr)
- {
- tree = *treePtrPtr;
- }
- else
- {
- btInverseDynamics::btMultiBodyTreeCreator id_creator;
- if (-1 == id_creator.createFromBtMultiBody(multiBody, false))
- {
-
- }
- else
- {
- tree = btInverseDynamics::CreateMultiBodyTree(id_creator);
- m_inverseDynamicsBodies.insert(multiBody, tree);
- }
- }
-
- return tree;
- }
-
- };
- void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper)
- {
- if (guiHelper)
- {
- guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
- } else
- {
- if (m_data->m_guiHelper && m_data->m_dynamicsWorld && m_data->m_dynamicsWorld->getDebugDrawer())
- {
- m_data->m_dynamicsWorld->setDebugDrawer(0);
- }
- }
- m_data->m_guiHelper = guiHelper;
- }
- PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
- {
- m_data = new PhysicsServerCommandProcessorInternalData();
- createEmptyDynamicsWorld();
- m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
- m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
- }
- PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
- {
- deleteDynamicsWorld();
- if (m_data->m_commandLogger)
- {
- delete m_data->m_commandLogger;
- m_data->m_commandLogger = 0;
- }
- delete m_data;
- }
- void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
- {
- ///collision configuration contains default setup for memory, collision setup
- m_data->m_collisionConfiguration = new btDefaultCollisionConfiguration();
- //m_collisionConfiguration->setConvexConvexMultipointIterations();
- ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
- m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration);
- m_data->m_broadphase = new btDbvtBroadphase();
- m_data->m_solver = new btMultiBodyConstraintSolver;
- m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
- //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
- m_data->m_dynamicsWorld->getCollisionObjectArray().reserve(8192);
- m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
- m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
- m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
- }
- void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies()
- {
- for (int i = 0; i < m_data->m_inverseDynamicsBodies.size(); i++)
- {
- btInverseDynamics::MultiBodyTree** treePtrPtr = m_data->m_inverseDynamicsBodies.getAtIndex(i);
- if (treePtrPtr)
- {
- btInverseDynamics::MultiBodyTree* tree = *treePtrPtr;
- delete tree;
- }
- }
- m_data->m_inverseDynamicsBodies.clear();
- }
- void PhysicsServerCommandProcessor::deleteDynamicsWorld()
- {
- deleteCachedInverseDynamicsBodies();
- for (int i=0;i<m_data->m_multiBodyJointFeedbacks.size();i++)
- {
- delete m_data->m_multiBodyJointFeedbacks[i];
- }
- m_data->m_multiBodyJointFeedbacks.clear();
- for (int i=0;i<m_data->m_worldImporters.size();i++)
- {
- delete m_data->m_worldImporters[i];
- }
- m_data->m_worldImporters.clear();
- for (int i=0;i<m_data->m_urdfLinkNameMapper.size();i++)
- {
- delete m_data->m_urdfLinkNameMapper[i];
- }
- m_data->m_urdfLinkNameMapper.clear();
- for (int i=0;i<m_data->m_strings.size();i++)
- {
- delete m_data->m_strings[i];
- }
- m_data->m_strings.clear();
- btAlignedObjectArray<btTypedConstraint*> constraints;
- btAlignedObjectArray<btMultiBodyConstraint*> mbconstraints;
- if (m_data->m_dynamicsWorld)
- {
- int i;
- for (i = m_data->m_dynamicsWorld->getNumConstraints() - 1; i >= 0; i--)
- {
- btTypedConstraint* constraint =m_data->m_dynamicsWorld->getConstraint(i);
- constraints.push_back(constraint);
- m_data->m_dynamicsWorld->removeConstraint(constraint);
- }
- for (i=m_data->m_dynamicsWorld->getNumMultiBodyConstraints()-1;i>=0;i--)
- {
- btMultiBodyConstraint* mbconstraint = m_data->m_dynamicsWorld->getMultiBodyConstraint(i);
- mbconstraints.push_back(mbconstraint);
- m_data->m_dynamicsWorld->removeMultiBodyConstraint(mbconstraint);
- }
- for (i = m_data->m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
- {
- btCollisionObject* obj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i];
- btRigidBody* body = btRigidBody::upcast(obj);
- if (body && body->getMotionState())
- {
- delete body->getMotionState();
- }
- m_data->m_dynamicsWorld->removeCollisionObject(obj);
- delete obj;
- }
- for (i=m_data->m_dynamicsWorld->getNumMultibodies()-1;i>=0;i--)
- {
- btMultiBody* mb = m_data->m_dynamicsWorld->getMultiBody(i);
- m_data->m_dynamicsWorld->removeMultiBody(mb);
- delete mb;
- }
- }
- for (int i=0;i<constraints.size();i++)
- {
- delete constraints[i];
- }
- constraints.clear();
- for (int i=0;i<mbconstraints.size();i++)
- {
- delete mbconstraints[i];
- }
- mbconstraints.clear();
- //delete collision shapes
- for (int j = 0; j<m_data->m_collisionShapes.size(); j++)
- {
- btCollisionShape* shape = m_data->m_collisionShapes[j];
- delete shape;
- }
- m_data->m_collisionShapes.clear();
- delete m_data->m_dynamicsWorld;
- m_data->m_dynamicsWorld=0;
- delete m_data->m_remoteDebugDrawer;
- m_data->m_remoteDebugDrawer =0;
- delete m_data->m_solver;
- m_data->m_solver=0;
- delete m_data->m_broadphase;
- m_data->m_broadphase=0;
- delete m_data->m_dispatcher;
- m_data->m_dispatcher=0;
- delete m_data->m_collisionConfiguration;
- m_data->m_collisionConfiguration=0;
- }
- bool PhysicsServerCommandProcessor::supportsJointMotor(btMultiBody* mb, int mbLinkIndex)
- {
- bool canHaveMotor = (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute
- ||mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::ePrismatic);
- return canHaveMotor;
- }
- //for testing, create joint motors for revolute and prismatic joints
- void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb)
- {
- int numLinks = mb->getNumLinks();
- for (int i=0;i<numLinks;i++)
- {
- int mbLinkIndex = i;
- if (supportsJointMotor(mb,mbLinkIndex))
- {
- float maxMotorImpulse = 1.f;
- int dof = 0;
- btScalar desiredVelocity = 0.f;
- btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,dof,desiredVelocity,maxMotorImpulse);
- motor->setPositionTarget(0, 0);
- motor->setVelocityTarget(0, 1);
- //motor->setRhsClamp(gRhsClamp);
- //motor->setMaxAppliedImpulse(0);
- mb->getLink(mbLinkIndex).m_userPtr = motor;
- m_data->m_dynamicsWorld->addMultiBodyConstraint(motor);
- motor->finalizeMultiDof();
- }
- }
- }
- bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody)
- {
- btAssert(m_data->m_dynamicsWorld);
- if (!m_data->m_dynamicsWorld)
- {
- b3Error("loadSdf: No valid m_dynamicsWorld");
- return false;
- }
- m_data->m_sdfRecentLoadedBodies.clear();
- BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
- bool useFixedBase = false;
- bool loadOk = u2b.loadSDF(fileName, useFixedBase);
- if (loadOk)
- {
- for (int i=0;i<u2b.getNumAllocatedCollisionShapes();i++)
- {
- btCollisionShape* shape =u2b.getAllocatedCollisionShape(i);
- m_data->m_collisionShapes.push_back(shape);
- }
- btTransform rootTrans;
- rootTrans.setIdentity();
- if (m_data->m_verboseOutput)
- {
- b3Printf("loaded %s OK!", fileName);
- }
- SaveWorldObjectData sd;
- sd.m_fileName = fileName;
- for (int m =0; m<u2b.getNumModels();m++)
- {
- u2b.activateModel(m);
- btMultiBody* mb = 0;
- btRigidBody* rb = 0;
- //get a body index
- int bodyUniqueId = m_data->allocHandle();
- InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
-
- sd.m_bodyUniqueIds.push_back(bodyUniqueId);
- u2b.setBodyUniqueId(bodyUniqueId);
- {
- btScalar mass = 0;
- bodyHandle->m_rootLocalInertialFrame.setIdentity();
- btVector3 localInertiaDiagonal(0,0,0);
- int urdfLinkIndex = u2b.getRootLinkIndex();
- u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
- }
- //todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
- int rootLinkIndex = u2b.getRootLinkIndex();
- b3Printf("urdf root link index = %d\n",rootLinkIndex);
- MyMultiBodyCreator creation(m_data->m_guiHelper);
- u2b.getRootTransformInWorld(rootTrans);
- ConvertURDF2Bullet(u2b,creation, rootTrans,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),CUF_USE_SDF);
- mb = creation.getBulletMultiBody();
- rb = creation.getRigidBody();
- if (rb)
- rb->setUserIndex2(bodyUniqueId);
- if (mb)
- mb->setUserIndex2(bodyUniqueId);
-
- if (mb)
- {
- bodyHandle->m_multiBody = mb;
-
- m_data->m_sdfRecentLoadedBodies.push_back(bodyUniqueId);
- createJointMotors(mb);
- //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
- bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
- for (int i=0;i<mb->getNumLinks();i++)
- {
- //disable serialization of the collision objects
- int urdfLinkIndex = creation.m_mb2urdfLink[i];
- btScalar mass;
- btVector3 localInertiaDiagonal(0,0,0);
- btTransform localInertialFrame;
- u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame);
- bodyHandle->m_linkLocalInertialFrames.push_back(localInertialFrame);
- std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str());
- m_data->m_strings.push_back(linkName);
- mb->getLink(i).m_linkName = linkName->c_str();
- std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str());
- m_data->m_strings.push_back(jointName);
- mb->getLink(i).m_jointName = jointName->c_str();
- }
- std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
- m_data->m_strings.push_back(baseName);
- mb->setBaseName(baseName->c_str());
- } else
- {
- b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later.");
- bodyHandle->m_rigidBody = rb;
- }
- }
-
- m_data->m_saveWorldBodyData.push_back(sd);
- }
- return loadOk;
- }
- bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
- bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes)
- {
- btAssert(m_data->m_dynamicsWorld);
- if (!m_data->m_dynamicsWorld)
- {
- b3Error("loadUrdf: No valid m_dynamicsWorld");
- return false;
- }
- BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
- bool loadOk = u2b.loadURDF(fileName, useFixedBase);
- if (loadOk)
- {
- //get a body index
- int bodyUniqueId = m_data->allocHandle();
- if (bodyUniqueIdPtr)
- *bodyUniqueIdPtr= bodyUniqueId;
- //quick prototype of 'save world' for crude world editing
- {
- SaveWorldObjectData sd;
- sd.m_fileName = fileName;
- sd.m_bodyUniqueIds.push_back(bodyUniqueId);
- m_data->m_saveWorldBodyData.push_back(sd);
- }
- u2b.setBodyUniqueId(bodyUniqueId);
- InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
-
- {
- btScalar mass = 0;
- bodyHandle->m_rootLocalInertialFrame.setIdentity();
- btVector3 localInertiaDiagonal(0,0,0);
- int urdfLinkIndex = u2b.getRootLinkIndex();
- u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
- }
- if (m_data->m_verboseOutput)
- {
- b3Printf("loaded %s OK!", fileName);
- }
- btTransform tr;
- tr.setIdentity();
- tr.setOrigin(pos);
- tr.setRotation(orn);
- //int rootLinkIndex = u2b.getRootLinkIndex();
- // printf("urdf root link index = %d\n",rootLinkIndex);
- MyMultiBodyCreator creation(m_data->m_guiHelper);
- ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
- for (int i=0;i<u2b.getNumAllocatedCollisionShapes();i++)
- {
- btCollisionShape* shape =u2b.getAllocatedCollisionShape(i);
- m_data->m_collisionShapes.push_back(shape);
- }
- btMultiBody* mb = creation.getBulletMultiBody();
- btRigidBody* rb = creation.getRigidBody();
- if (useMultiBody)
- {
- if (mb)
- {
- mb->setUserIndex2(bodyUniqueId);
- bodyHandle->m_multiBody = mb;
- createJointMotors(mb);
- //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
- UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
- m_data->m_urdfLinkNameMapper.push_back(util);
- util->m_mb = mb;
- util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient);
- //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
- util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0);
- bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
- for (int i=0;i<mb->getNumLinks();i++)
- {
- //disable serialization of the collision objects
- util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0);
- int urdfLinkIndex = creation.m_mb2urdfLink[i];
- btScalar mass;
- btVector3 localInertiaDiagonal(0,0,0);
- btTransform localInertialFrame;
- u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame);
- bodyHandle->m_linkLocalInertialFrames.push_back(localInertialFrame);
- std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str());
- m_data->m_strings.push_back(linkName);
- util->m_memSerializer->registerNameForPointer(linkName->c_str(),linkName->c_str());
- mb->getLink(i).m_linkName = linkName->c_str();
- std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str());
- m_data->m_strings.push_back(jointName);
- util->m_memSerializer->registerNameForPointer(jointName->c_str(),jointName->c_str());
- mb->getLink(i).m_jointName = jointName->c_str();
- }
- std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
- m_data->m_strings.push_back(baseName);
- util->m_memSerializer->registerNameForPointer(baseName->c_str(),baseName->c_str());
- mb->setBaseName(baseName->c_str());
- util->m_memSerializer->insertHeader();
- int len = mb->calculateSerializeBufferSize();
- btChunk* chunk = util->m_memSerializer->allocate(len,1);
- const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer);
- util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb);
- return true;
- } else
- {
- b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later.");
- return false;
- }
- } else
- {
- if (rb)
- {
- bodyHandle->m_rigidBody = rb;
- rb->setUserIndex2(bodyUniqueId);
- return true;
- }
- }
- }
- return false;
- }
- void PhysicsServerCommandProcessor::replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes)
- {
- if (m_data->m_logPlayback)
- {
- SharedMemoryCommand clientCmd;
- SharedMemoryStatus serverStatus;
- bool hasCommand = m_data->m_logPlayback->processNextCommand(&clientCmd);
- if (hasCommand)
- {
- processCommand(clientCmd,serverStatus,bufferServerToClient,bufferSizeInBytes);
- }
- }
- }
- int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes)
- {
- int streamSizeInBytes = 0;
- //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
- InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
- btMultiBody* mb = bodyHandle->m_multiBody;
- if (mb)
- {
- UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
- m_data->m_urdfLinkNameMapper.push_back(util);
- util->m_mb = mb;
- util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient);
- //disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
- util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0);
- if (mb->getBaseName())
- {
- util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName());
- }
- bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
- for (int i=0;i<mb->getNumLinks();i++)
- {
- //disable serialization of the collision objects
- util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0);
- util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_linkName,mb->getLink(i).m_linkName);
- util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_jointName,mb->getLink(i).m_jointName);
- }
- util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName());
- util->m_memSerializer->insertHeader();
- int len = mb->calculateSerializeBufferSize();
- btChunk* chunk = util->m_memSerializer->allocate(len,1);
- const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer);
- util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb);
- streamSizeInBytes = util->m_memSerializer->getCurrentBufferSize();
- }
- return streamSizeInBytes;
- }
- bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes )
- {
- bool hasStatus = false;
- {
- ///we ignore overflow of integer for now
- {
- //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands
- //const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0];
- #if 1
- if (m_data->m_commandLogger)
- {
- m_data->m_commandLogger->logCommand(clientCmd);
- }
- #endif
- //m_data->m_testBlock1->m_numProcessedClientCommands++;
- //no timestamp yet
- int timeStamp = 0;
-
- //catch uninitialized cases
- serverStatusOut.m_type = CMD_INVALID_STATUS;
- //consume the command
- switch (clientCmd.m_type)
- {
- #if 0
- case CMD_SEND_BULLET_DATA_STREAM:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength);
- }
- btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
- m_data->m_worldImporters.push_back(worldImporter);
- bool completedOk = worldImporter->loadFileFromMemory(m_data->m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength);
- if (completedOk)
- {
- SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp);
- m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
- m_data->submitServerStatus(status);
- } else
- {
- SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,clientCmd.m_sequenceNumber,timeStamp);
- m_data->submitServerStatus(status);
- }
- break;
- }
- #endif
- case CMD_REQUEST_DEBUG_LINES:
- {
- int curFlags =m_data->m_remoteDebugDrawer->getDebugMode();
- int debugMode = clientCmd.m_requestDebugLinesArguments.m_debugMode;//clientCmd.btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb;
- int startingLineIndex = clientCmd.m_requestDebugLinesArguments.m_startingLineIndex;
- if (startingLineIndex<0)
- {
- b3Warning("startingLineIndex should be non-negative");
- startingLineIndex = 0;
- }
- if (clientCmd.m_requestDebugLinesArguments.m_startingLineIndex==0)
- {
- m_data->m_remoteDebugDrawer->m_lines2.resize(0);
- //|btIDebugDraw::DBG_DrawAabb|
- // btIDebugDraw::DBG_DrawConstraints |btIDebugDraw::DBG_DrawConstraintLimits ;
- m_data->m_remoteDebugDrawer->setDebugMode(debugMode);
- btIDebugDraw* oldDebugDrawer = m_data->m_dynamicsWorld->getDebugDrawer();
- m_data->m_dynamicsWorld->setDebugDrawer(m_data->m_remoteDebugDrawer);
- m_data->m_dynamicsWorld->debugDrawWorld();
- m_data->m_dynamicsWorld->setDebugDrawer(oldDebugDrawer);
- m_data->m_remoteDebugDrawer->setDebugMode(curFlags);
- }
- //9 floats per line: 3 floats for 'from', 3 floats for 'to' and 3 floats for 'color'
- int maxNumLines = bufferSizeInBytes/(sizeof(float)*9)-1;
- if (startingLineIndex >m_data->m_remoteDebugDrawer->m_lines2.size())
- {
- b3Warning("m_startingLineIndex exceeds total number of debug lines");
- startingLineIndex =m_data->m_remoteDebugDrawer->m_lines2.size();
- }
- int numLines = btMin(maxNumLines,m_data->m_remoteDebugDrawer->m_lines2.size()-startingLineIndex);
- if (numLines)
- {
- float* linesFrom = (float*)bufferServerToClient;
- float* linesTo = (float*)(bufferServerToClient+numLines*3*sizeof(float));
- float* linesColor = (float*)(bufferServerToClient+2*numLines*3*sizeof(float));
- for (int i=0;i<numLines;i++)
- {
- linesFrom[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.x();
- linesTo[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.x();
- linesColor[i*3] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.x();
- linesFrom[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.y();
- linesTo[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.y();
- linesColor[i*3+1] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.y();
- linesFrom[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_from.z();
- linesTo[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_to.z();
- linesColor[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.z();
- }
- }
- serverStatusOut.m_type = CMD_DEBUG_LINES_COMPLETED;
- serverStatusOut.m_sendDebugLinesArgs.m_numDebugLines = numLines;
- serverStatusOut.m_sendDebugLinesArgs.m_startingLineIndex = startingLineIndex;
- serverStatusOut.m_sendDebugLinesArgs.m_numRemainingDebugLines = m_data->m_remoteDebugDrawer->m_lines2.size()-(startingLineIndex+numLines);
- hasStatus = true;
- break;
- }
- case CMD_REQUEST_CAMERA_IMAGE_DATA:
- {
- int startPixelIndex = clientCmd.m_requestPixelDataArguments.m_startPixelIndex;
- int width = clientCmd.m_requestPixelDataArguments.m_pixelWidth;
- int height = clientCmd.m_requestPixelDataArguments.m_pixelHeight;
- int numPixelsCopied = 0;
- if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
- {
- //m_data->m_guiHelper->copyCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,clientCmd.m_requestPixelDataArguments.m_projectionMatrix,0,0,0,0,0,width,height,0);
- }
- else
- {
- if ((clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) &&
- (clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0)
- {
- m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
- clientCmd.m_requestPixelDataArguments.m_pixelHeight);
- }
- m_data->m_visualConverter.getWidthAndHeight(width,height);
- }
- int numTotalPixels = width*height;
- int numRemainingPixels = numTotalPixels - startPixelIndex;
- if (numRemainingPixels>0)
- {
- int totalBytesPerPixel = 4+4+4;//4 for rgb, 4 for depth, 4 for segmentation mask
- int maxNumPixels = bufferSizeInBytes/totalBytesPerPixel-1;
- unsigned char* pixelRGBA = (unsigned char*)bufferServerToClient;
- int numRequestedPixels = btMin(maxNumPixels,numRemainingPixels);
- float* depthBuffer = (float*)(bufferServerToClient+numRequestedPixels*4);
- int* segmentationMaskBuffer = (int*)(bufferServerToClient+numRequestedPixels*8);
- if ((clientCmd.m_updateFlags & ER_BULLET_HARDWARE_OPENGL)!=0)
- {
- m_data->m_guiHelper->copyCameraImageData(clientCmd.m_requestPixelDataArguments.m_viewMatrix,
- clientCmd.m_requestPixelDataArguments.m_projectionMatrix,pixelRGBA,numRequestedPixels,
- depthBuffer,numRequestedPixels,
- segmentationMaskBuffer, numRequestedPixels,
- startPixelIndex,width,height,&numPixelsCopied);
- } else
- {
- if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0)
- {
- // printf("-------------------------------\nRendering\n");
- if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
- {
- m_data->m_visualConverter.render(
- clientCmd.m_requestPixelDataArguments.m_viewMatrix,
- clientCmd.m_requestPixelDataArguments.m_projectionMatrix);
- } else
- {
- m_data->m_visualConverter.render();
- }
- }
- m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,
- depthBuffer,numRequestedPixels,
- segmentationMaskBuffer, numRequestedPixels,
- startPixelIndex,&width,&height,&numPixelsCopied);
- }
- //each pixel takes 4 RGBA values and 1 float = 8 bytes
- } else
- {
- }
- serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED;
- serverStatusOut.m_sendPixelDataArguments.m_numPixelsCopied = numPixelsCopied;
- serverStatusOut.m_sendPixelDataArguments.m_numRemainingPixels = numRemainingPixels - numPixelsCopied;
- serverStatusOut.m_sendPixelDataArguments.m_startingPixelIndex = startPixelIndex;
- serverStatusOut.m_sendPixelDataArguments.m_imageWidth = width;
- serverStatusOut.m_sendPixelDataArguments.m_imageHeight= height;
- hasStatus = true;
- break;
- }
- case CMD_REQUEST_BODY_INFO:
- {
- const SdfRequestInfoArgs& sdfInfoArgs = clientCmd.m_sdfRequestInfoArgs;
- //stream info into memory
- int streamSizeInBytes = createBodyInfoStream(sdfInfoArgs.m_bodyUniqueId, bufferServerToClient, bufferSizeInBytes);
- serverStatusOut.m_type = CMD_BODY_INFO_COMPLETED;
- serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = sdfInfoArgs.m_bodyUniqueId;
- serverStatusOut.m_dataStreamArguments.m_streamChunkLength = streamSizeInBytes;
- hasStatus = true;
- break;
- }
- case CMD_SAVE_WORLD:
- {
- ///this is a very rudimentary way to save the state of the world, for scene authoring
- ///many todo's, for example save the state of motor controllers etc.
-
- {
- //saveWorld(clientCmd.m_sdfArguments.m_sdfFileName);
- FILE* f = fopen(clientCmd.m_sdfArguments.m_sdfFileName,"w");
- if (f)
- {
- char line[1024];
- {
- sprintf(line,"import pybullet as p\n");
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- {
- sprintf(line,"p.connect(p.SHARED_MEMORY)\n");
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- //for each objects ...
- for (int i=0;i<m_data->m_saveWorldBodyData.size();i++)
- {
- SaveWorldObjectData& sd = m_data->m_saveWorldBodyData[i];
- for (int i=0;i<sd.m_bodyUniqueIds.size();i++)
- {
- {
- int bodyUniqueId = sd.m_bodyUniqueIds[i];
- InteralBodyData* body = m_data->getHandle(bodyUniqueId);
- if (body)
- {
- if (body->m_multiBody)
- {
- btMultiBody* mb = body->m_multiBody;
-
- btTransform comTr = mb->getBaseWorldTransform();
- btTransform tr = comTr * body->m_rootLocalInertialFrame.inverse();
-
- if (strstr(sd.m_fileName.c_str(),".urdf"))
- {
- sprintf(line,"objects = [p.loadURDF(\"%s\", %f,%f,%f,%f,%f,%f,%f)]\n",sd.m_fileName.c_str(),
- tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2],
- tr.getRotation()[0],tr.getRotation()[1],tr.getRotation()[2],tr.getRotation()[3]);
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- if (strstr(sd.m_fileName.c_str(),".sdf") && i==0)
- {
- sprintf(line,"objects = p.loadSDF(\"%s\")\n",sd.m_fileName.c_str());
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- if (strstr(sd.m_fileName.c_str(),".sdf") || ((strstr(sd.m_fileName.c_str(),".urdf")) && mb->getNumLinks()) )
- {
- sprintf(line,"ob = objects[%d]\n",i);
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- if (strstr(sd.m_fileName.c_str(),".sdf"))
- {
- sprintf(line,"p.resetBasePositionAndOrientation(ob,[%f,%f,%f],[%f,%f,%f,%f])\n",
- comTr.getOrigin()[0],comTr.getOrigin()[1],comTr.getOrigin()[2],
- comTr.getRotation()[0],comTr.getRotation()[1],comTr.getRotation()[2],comTr.getRotation()[3]);
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- if (mb->getNumLinks())
- {
- {
- sprintf(line,"jointPositions=[");
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- for (int i=0;i<mb->getNumLinks();i++)
- {
- btScalar jointPos = mb->getJointPosMultiDof(i)[0];
- if (i<mb->getNumLinks()-1)
- {
- sprintf(line," %f,",jointPos);
- int len = strlen(line);
- fwrite(line,len,1,f);
- } else
- {
- sprintf(line," %f ",jointPos);
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- }
- {
- sprintf(line,"]\nfor jointIndex in range (p.getNumJoints(ob)):\n\tp.resetJointState(ob,jointIndex,jointPositions[jointIndex])\n\n");
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- }
- } else
- {
- //todo: btRigidBody/btSoftBody etc case
- }
- }
- }
-
- }
-
- //for URDF, load at origin, then reposition...
-
- struct SaveWorldObjectData
- {
- b3AlignedObjectArray<int> m_bodyUniqueIds;
- std::string m_fileName;
- };
- }
- {
- btVector3 grav=this->m_data->m_dynamicsWorld->getGravity();
- sprintf(line,"p.setGravity(%f,%f,%f)\n",grav[0],grav[1],grav[2]);
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
-
- {
- sprintf(line,"p.stepSimulation()\np.disconnect()\n");
- int len = strlen(line);
- fwrite(line,len,1,f);
- }
- fclose(f);
- }
- serverStatusOut.m_type = CMD_SAVE_WORLD_COMPLETED;
- hasStatus = true;
- break;
- }
- serverStatusOut.m_type = CMD_SAVE_WORLD_FAILED;
- hasStatus = true;
- break;
- }
- case CMD_LOAD_SDF:
- {
- const SdfArgs& sdfArgs = clientCmd.m_sdfArguments;
- if (m_data->m_verboseOutput)
- {
- b3Printf("Processed CMD_LOAD_SDF:%s", sdfArgs.m_sdfFileName);
- }
- bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? sdfArgs.m_useMultiBody : true;
- bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody);
- if (completedOk)
- {
- //serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
- serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size();
- int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies);
- for (int i=0;i<maxBodies;i++)
- {
- serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[i] = m_data->m_sdfRecentLoadedBodies[i];
- }
- serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED;
- } else
- {
- serverStatusOut.m_type = CMD_SDF_LOADING_FAILED;
- }
- hasStatus = true;
- break;
- }
- case CMD_LOAD_URDF:
- {
- const UrdfArgs& urdfArgs = clientCmd.m_urdfArguments;
- if (m_data->m_verboseOutput)
- {
- b3Printf("Processed CMD_LOAD_URDF:%s", urdfArgs.m_urdfFileName);
- }
- btAssert((clientCmd.m_updateFlags&URDF_ARGS_FILE_NAME) !=0);
- btAssert(urdfArgs.m_urdfFileName);
- btVector3 initialPos(0,0,0);
- btQuaternion initialOrn(0,0,0,1);
- if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_POSITION)
- {
- initialPos[0] = urdfArgs.m_initialPosition[0];
- initialPos[1] = urdfArgs.m_initialPosition[1];
- initialPos[2] = urdfArgs.m_initialPosition[2];
- }
- if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_ORIENTATION)
- {
- initialOrn[0] = urdfArgs.m_initialOrientation[0];
- initialOrn[1] = urdfArgs.m_initialOrientation[1];
- initialOrn[2] = urdfArgs.m_initialOrientation[2];
- initialOrn[3] = urdfArgs.m_initialOrientation[3];
- }
- bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? urdfArgs.m_useMultiBody : true;
- bool useFixedBase = (clientCmd.m_updateFlags & URDF_ARGS_USE_FIXED_BASE) ? urdfArgs.m_useFixedBase: false;
- int bodyUniqueId;
- //load the actual URDF and send a report: completed or failed
- bool completedOk = loadUrdf(urdfArgs.m_urdfFileName,
- initialPos,initialOrn,
- useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes);
- if (completedOk)
- {
- m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
- serverStatusOut.m_type = CMD_URDF_LOADING_COMPLETED;
- serverStatusOut.m_dataStreamArguments.m_streamChunkLength = 0;
- if (m_data->m_urdfLinkNameMapper.size())
- {
- serverStatusOut.m_dataStreamArguments.m_streamChunkLength = m_data->m_urdfLinkNameMapper.at(m_data->m_urdfLinkNameMapper.size()-1)->m_memSerializer->getCurrentBufferSize();
- }
- serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = bodyUniqueId;
- hasStatus = true;
- } else
- {
- serverStatusOut.m_type = CMD_URDF_LOADING_FAILED;
- hasStatus = true;
- }
- break;
- }
- case CMD_CREATE_SENSOR:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Processed CMD_CREATE_SENSOR");
- }
- int bodyUniqueId = clientCmd.m_createSensorArguments.m_bodyUniqueId;
- InteralBodyData* body = m_data->getHandle(bodyUniqueId);
- if (body && body->m_multiBody)
- {
- btMultiBody* mb = body->m_multiBody;
- btAssert(mb);
- for (int i=0;i<clientCmd.m_createSensorArguments.m_numJointSensorChanges;i++)
- {
- int jointIndex = clientCmd.m_createSensorArguments.m_jointIndex[i];
- if (clientCmd.m_createSensorArguments.m_enableJointForceSensor[i])
- {
- if (mb->getLink(jointIndex).m_jointFeedback)
- {
- b3Warning("CMD_CREATE_SENSOR: sensor for joint [%d] already enabled", jointIndex);
- } else
- {
- btMultiBodyJointFeedback* fb = new btMultiBodyJointFeedback();
- fb->m_reactionForces.setZero();
- mb->getLink(jointIndex).m_jointFeedback = fb;
- m_data->m_multiBodyJointFeedbacks.push_back(fb);
- };
- } else
- {
- if (mb->getLink(jointIndex).m_jointFeedback)
- {
- m_data->m_multiBodyJointFeedbacks.remove(mb->getLink(jointIndex).m_jointFeedback);
- delete mb->getLink(jointIndex).m_jointFeedback;
- mb->getLink(jointIndex).m_jointFeedback=0;
- } else
- {
- b3Warning("CMD_CREATE_SENSOR: cannot perform sensor removal request, no sensor on joint [%d]", jointIndex);
- };
- }
- }
- } else
- {
- b3Warning("No btMultiBody in the world. btRigidBody/btTypedConstraint sensor not hooked up yet");
- }
- #if 0
- //todo(erwincoumans) here is some sample code to hook up a force/torque sensor for btTypedConstraint/btRigidBody
- /*
- for (int i=0;i<m_data->m_dynamicsWorld->getNumConstraints();i++)
- {
- btTypedConstraint* c = m_data->m_dynamicsWorld->getConstraint(i);
- btJointFeedback* fb = new btJointFeedback();
- m_data->m_jointFeedbacks.push_back(fb);
- c->setJointFeedback(fb);
- }
- */
- #endif
- serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_SEND_DESIRED_STATE:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Processed CMD_SEND_DESIRED_STATE");
- }
- int bodyUniqueId = clientCmd.m_sendDesiredStateCommandArgument.m_bodyUniqueId;
- InteralBodyData* body = m_data->getHandle(bodyUniqueId);
- if (body && body->m_multiBody)
- {
- btMultiBody* mb = body->m_multiBody;
- btAssert(mb);
- switch (clientCmd.m_sendDesiredStateCommandArgument.m_controlMode)
- {
- case CONTROL_MODE_TORQUE:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Using CONTROL_MODE_TORQUE");
- }
- // mb->clearForcesAndTorques();
- int torqueIndex = 6;
- if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
- {
- for (int link=0;link<mb->getNumLinks();link++)
- {
- for (int dof=0;dof<mb->getLink(link).m_dofCount;dof++)
- {
- double torque = 0.f;
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[torqueIndex]&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
- {
- torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex];
- mb->addJointTorqueMultiDof(link,dof,torque);
- }
- torqueIndex++;
- }
- }
- }
- break;
- }
- case CONTROL_MODE_VELOCITY:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Using CONTROL_MODE_VELOCITY");
- }
- int numMotors = 0;
- //find the joint motors and apply the desired velocity and maximum force/torque
- {
- int dofIndex = 6;//skip the 3 linear + 3 angular degree of freedom entries of the base
- for (int link=0;link<mb->getNumLinks();link++)
- {
- if (supportsJointMotor(mb,link))
- {
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr;
- if (motor)
- {
- btScalar desiredVelocity = 0.f;
- bool hasDesiredVelocity = false;
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_QDOT)!=0)
- {
- desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex];
- btScalar kd = 0.1f;
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] & SIM_DESIRED_STATE_HAS_KD)!=0)
- {
- kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[dofIndex];
- }
- motor->setVelocityTarget(desiredVelocity,kd);
- btScalar kp = 0.f;
- motor->setPositionTarget(0,kp);
- hasDesiredVelocity = true;
- }
- if (hasDesiredVelocity)
- {
- btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime;
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
- {
- maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime;
- }
- motor->setMaxAppliedImpulse(maxImp);
- }
- numMotors++;
- }
- }
- dofIndex += mb->getLink(link).m_dofCount;
- }
- }
- break;
- }
- case CONTROL_MODE_POSITION_VELOCITY_PD:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Using CONTROL_MODE_POSITION_VELOCITY_PD");
- }
- //compute the force base on PD control
- int numMotors = 0;
- //find the joint motors and apply the desired velocity and maximum force/torque
- {
- int velIndex = 6;//skip the 3 linear + 3 angular degree of freedom velocity entries of the base
- int posIndex = 7;//skip 3 positional and 4 orientation (quaternion) positional degrees of freedom of the base
- for (int link=0;link<mb->getNumLinks();link++)
- {
- if (supportsJointMotor(mb,link))
- {
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr;
- if (motor)
- {
- bool hasDesiredPosOrVel = false;
- btScalar kp = 0.f;
- btScalar kd = 0.f;
- btScalar desiredVelocity = 0.f;
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_QDOT)!=0)
- {
- hasDesiredPosOrVel = true;
- desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex];
- kd = 0.1;
- }
- btScalar desiredPosition = 0.f;
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[posIndex] & SIM_DESIRED_STATE_HAS_Q)!=0)
- {
- hasDesiredPosOrVel = true;
- desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex];
- kp = 0.1;
- }
- if (hasDesiredPosOrVel)
- {
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KP)!=0)
- {
- kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex];
- }
- if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KD)!=0)
- {
- kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex];
- }
- motor->setVelocityTarget(desiredVelocity,kd);
- motor->setPositionTarget(desiredPosition,kp);
- btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime;
- if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0)
- maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime;
- motor->setMaxAppliedImpulse(maxImp);
- }
- numMotors++;
- }
- }
- velIndex += mb->getLink(link).m_dofCount;
- posIndex += mb->getLink(link).m_posVarCount;
- }
- }
- break;
- }
- default:
- {
- b3Warning("m_controlMode not implemented yet");
- break;
- }
- }
- }
- serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_REQUEST_ACTUAL_STATE:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Sending the actual state (Q,U)");
- }
- int bodyUniqueId = clientCmd.m_requestActualStateInformationCommandArgument.m_bodyUniqueId;
- InteralBodyData* body = m_data->getHandle(bodyUniqueId);
- if (body && body->m_multiBody)
- {
- btMultiBody* mb = body->m_multiBody;
- SharedMemoryStatus& serverCmd = serverStatusOut;
- serverStatusOut.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
- serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
- int totalDegreeOfFreedomQ = 0;
- int totalDegreeOfFreedomU = 0;
- if (mb->getNumLinks()>= MAX_DEGREE_OF_FREEDOM)
- {
- serverStatusOut.m_type = CMD_ACTUAL_STATE_UPDATE_FAILED;
- hasStatus = true;
- break;
- }
- //always add the base, even for static (non-moving objects)
- //so that we can easily move the 'fixed' base when needed
- //do we don't use this conditional "if (!mb->hasFixedBase())"
- {
- btTransform tr;
- tr.setOrigin(mb->getBasePos());
- tr.setRotation(mb->getWorldToBaseRot().inverse());
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[0] =
- body->m_rootLocalInertialFrame.getOrigin()[0];
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[1] =
- body->m_rootLocalInertialFrame.getOrigin()[1];
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[2] =
- body->m_rootLocalInertialFrame.getOrigin()[2];
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[3] =
- body->m_rootLocalInertialFrame.getRotation()[0];
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[4] =
- body->m_rootLocalInertialFrame.getRotation()[1];
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[5] =
- body->m_rootLocalInertialFrame.getRotation()[2];
- serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[6] =
- body->m_rootLocalInertialFrame.getRotation()[3];
- //base position in world space, carthesian
- serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2];
- //base orientation, quaternion x,y,z,w, in world space, carthesian
- serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3];
- totalDegreeOfFreedomQ +=7;//pos + quaternion
- //base linear velocity (in world space, carthesian)
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = mb->getBaseVel()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = mb->getBaseVel()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = mb->getBaseVel()[2];
- //base angular velocity (in world space, carthesian)
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = mb->getBaseOmega()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = mb->getBaseOmega()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[5] = mb->getBaseOmega()[2];
- totalDegreeOfFreedomU += 6;//3 linear and 3 angular DOF
- }
- for (int l=0;l<mb->getNumLinks();l++)
- {
- for (int d=0;d<mb->getLink(l).m_posVarCount;d++)
- {
- serverCmd.m_sendActualStateArgs.m_actualStateQ[totalDegreeOfFreedomQ++] = mb->getJointPosMultiDof(l)[d];
- }
- for (int d=0;d<mb->getLink(l).m_dofCount;d++)
- {
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[totalDegreeOfFreedomU++] = mb->getJointVelMultiDof(l)[d];
- }
- if (0 == mb->getLink(l).m_jointFeedback)
- {
- for (int d=0;d<6;d++)
- {
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+d]=0;
- }
- } else
- {
- btVector3 sensedForce = mb->getLink(l).m_jointFeedback->m_reactionForces.getLinear();
- btVector3 sensedTorque = mb->getLink(l).m_jointFeedback->m_reactionForces.getAngular();
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+0] = sensedForce[0];
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+1] = sensedForce[1];
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+2] = sensedForce[2];
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+3] = sensedTorque[0];
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+4] = sensedTorque[1];
- serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+5] = sensedTorque[2];
- }
- serverCmd.m_sendActualStateArgs.m_jointMotorForce[l] = 0;
- if (supportsJointMotor(mb,l))
- {
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)body->m_multiBody->getLink(l).m_userPtr;
- if (motor && m_data->m_physicsDeltaTime>btScalar(0))
- {
- btScalar force =motor->getAppliedImpulse(0)/m_data->m_physicsDeltaTime;
- serverCmd.m_sendActualStateArgs.m_jointMotorForce[l] =
- force;
- //if (force>0)
- //{
- // b3Printf("force = %f\n", force);
- //}
- }
- }
- btVector3 linkLocalInertialOrigin = body->m_linkLocalInertialFrames[l].getOrigin();
- btQuaternion linkLocalInertialRotation = body->m_linkLocalInertialFrames[l].getRotation();
- btVector3 linkCOMOrigin = mb->getLink(l).m_cachedWorldTransform.getOrigin();
- btQuaternion linkCOMRotation = mb->getLink(l).m_cachedWorldTransform.getRotation();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+0] = linkCOMOrigin.getX();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+1] = linkCOMOrigin.getY();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+2] = linkCOMOrigin.getZ();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+3] = linkCOMRotation.x();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+4] = linkCOMRotation.y();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+5] = linkCOMRotation.z();
- serverCmd.m_sendActualStateArgs.m_linkState[l*7+6] = linkCOMRotation.w();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+0] = linkLocalInertialOrigin.getX();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+1] = linkLocalInertialOrigin.getY();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+2] = linkLocalInertialOrigin.getZ();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+3] = linkLocalInertialRotation.x();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+4] = linkLocalInertialRotation.y();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+5] = linkLocalInertialRotation.z();
- serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+6] = linkLocalInertialRotation.w();
- }
- serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ;
- serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU;
- hasStatus = true;
- } else
- {
- if (body && body->m_rigidBody)
- {
- btRigidBody* rb = body->m_rigidBody;
- SharedMemoryStatus& serverCmd = serverStatusOut;
- serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_COMPLETED;
- serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId;
- int totalDegreeOfFreedomQ = 0;
- int totalDegreeOfFreedomU = 0;
- btTransform tr = rb->getWorldTransform();
- //base position in world space, carthesian
- serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2];
- //base orientation, quaternion x,y,z,w, in world space, carthesian
- serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2];
- serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3];
- totalDegreeOfFreedomQ +=7;//pos + quaternion
- //base linear velocity (in world space, carthesian)
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = rb->getLinearVelocity()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = rb->getLinearVelocity()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = rb->getLinearVelocity()[2];
- //base angular velocity (in world space, carthesian)
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = rb->getAngularVelocity()[0];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = rb->getAngularVelocity()[1];
- serverCmd.m_sendActualStateArgs.m_actualStateQdot[5] = rb->getAngularVelocity()[2];
- totalDegreeOfFreedomU += 6;//3 linear and 3 angular DOF
- serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ;
- serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU;
- hasStatus = true;
- } else
- {
- b3Warning("Request state but no multibody or rigid body available");
- SharedMemoryStatus& serverCmd = serverStatusOut;
- serverCmd.m_type = CMD_ACTUAL_STATE_UPDATE_FAILED;
- hasStatus = true;
- }
- }
- break;
- }
- case CMD_STEP_FORWARD_SIMULATION:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Step simulation request");
- b3Printf("CMD_STEP_FORWARD_SIMULATION clientCmd = %d\n", clientCmd.m_sequenceNumber);
- }
- ///todo(erwincoumans) move this damping inside Bullet
- for (int i=0;i<m_data->m_bodyHandles.size();i++)
- {
- applyJointDamping(i);
- }
-
-
-
- btScalar deltaTimeScaled = m_data->m_physicsDeltaTime*simTimeScalingFactor;
- if (m_data->m_numSimulationSubSteps > 0)
- {
- m_data->m_dynamicsWorld->stepSimulation(deltaTimeScaled, m_data->m_numSimulationSubSteps, m_data->m_physicsDeltaTime / m_data->m_numSimulationSubSteps);
- }
- else
- {
- m_data->m_dynamicsWorld->stepSimulation(deltaTimeScaled, 0);
- }
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_STEP_FORWARD_SIMULATION_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
- {
- if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME)
- {
- m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime;
- }
- if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION)
- {
- m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation;
- }
- if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY)
- {
- btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0],
- clientCmd.m_physSimParamArgs.m_gravityAcceleration[1],
- clientCmd.m_physSimParamArgs.m_gravityAcceleration[2]);
- this->m_data->m_dynamicsWorld->setGravity(grav);
- if (m_data->m_verboseOutput)
- {
- b3Printf("Updated Gravity: %f,%f,%f",grav[0],grav[1],grav[2]);
- }
- }
- if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS)
- {
- m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
- }
- if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS)
- {
- m_data->m_numSimulationSubSteps = clientCmd.m_physSimParamArgs.m_numSimulationSubSteps;
- }
- if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP)
- {
- m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = clientCmd.m_physSimParamArgs.m_defaultContactERP;
- }
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- };
- case CMD_INIT_POSE:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("Server Init Pose not implemented yet");
- }
- int bodyUniqueId = clientCmd.m_initPoseArgs.m_bodyUniqueId;
- InteralBodyData* body = m_data->getHandle(bodyUniqueId);
- if (body && body->m_multiBody)
- {
- btMultiBody* mb = body->m_multiBody;
- if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION)
- {
- btVector3 zero(0,0,0);
- btAssert(clientCmd.m_initPoseArgs.m_hasInitialStateQ[0] &&
- clientCmd.m_initPoseArgs.m_hasInitialStateQ[1] &&
- clientCmd.m_initPoseArgs.m_hasInitialStateQ[2]);
- mb->setBaseVel(zero);
- mb->setBasePos(btVector3(
- clientCmd.m_initPoseArgs.m_initialStateQ[0],
- clientCmd.m_initPoseArgs.m_initialStateQ[1],
- clientCmd.m_initPoseArgs.m_initialStateQ[2]));
- }
- if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION)
- {
- btAssert(clientCmd.m_initPoseArgs.m_hasInitialStateQ[3] &&
- clientCmd.m_initPoseArgs.m_hasInitialStateQ[4] &&
- clientCmd.m_initPoseArgs.m_hasInitialStateQ[5] &&
- clientCmd.m_initPoseArgs.m_hasInitialStateQ[6]);
- mb->setBaseOmega(btVector3(0,0,0));
- btQuaternion invOrn(clientCmd.m_initPoseArgs.m_initialStateQ[3],
- clientCmd.m_initPoseArgs.m_initialStateQ[4],
- clientCmd.m_initPoseArgs.m_initialStateQ[5],
- clientCmd.m_initPoseArgs.m_initialStateQ[6]);
- mb->setWorldToBaseRot(invOrn.inverse());
- }
- if (clientCmd.m_updateFlags & INIT_POSE_HAS_JOINT_STATE)
- {
- int dofIndex = 7;
- for (int i=0;i<mb->getNumLinks();i++)
- {
- if ( (clientCmd.m_initPoseArgs.m_hasInitialStateQ[dofIndex]) && (mb->getLink(i).m_dofCount==1))
- {
- mb->setJointPos(i,clientCmd.m_initPoseArgs.m_initialStateQ[dofIndex]);
- mb->setJointVel(i,0);
- }
- dofIndex += mb->getLink(i).m_dofCount;
- }
- }
- }
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_RESET_SIMULATION:
- {
- //clean up all data
- deleteCachedInverseDynamicsBodies();
- if (m_data && m_data->m_guiHelper)
- {
- m_data->m_guiHelper->removeAllGraphicsInstances();
- }
- if (m_data)
- {
- m_data->m_visualConverter.resetAll();
- }
- deleteDynamicsWorld();
- createEmptyDynamicsWorld();
- m_data->exitHandles();
- m_data->initHandles();
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED;
- hasStatus = true;
- m_data->m_hasGround = false;
- m_data->m_gripperRigidbodyFixed = 0;
- break;
- }
- case CMD_CREATE_RIGID_BODY:
- case CMD_CREATE_BOX_COLLISION_SHAPE:
- {
- btVector3 halfExtents(1,1,1);
- if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_HALF_EXTENTS)
- {
- halfExtents = btVector3(
- clientCmd.m_createBoxShapeArguments.m_halfExtentsX,
- clientCmd.m_createBoxShapeArguments.m_halfExtentsY,
- clientCmd.m_createBoxShapeArguments.m_halfExtentsZ);
- }
- btTransform startTrans;
- startTrans.setIdentity();
- if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_POSITION)
- {
- startTrans.setOrigin(btVector3(
- clientCmd.m_createBoxShapeArguments.m_initialPosition[0],
- clientCmd.m_createBoxShapeArguments.m_initialPosition[1],
- clientCmd.m_createBoxShapeArguments.m_initialPosition[2]));
- }
- if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_ORIENTATION)
- {
- startTrans.setRotation(btQuaternion(
- clientCmd.m_createBoxShapeArguments.m_initialOrientation[0],
- clientCmd.m_createBoxShapeArguments.m_initialOrientation[1],
- clientCmd.m_createBoxShapeArguments.m_initialOrientation[2],
- clientCmd.m_createBoxShapeArguments.m_initialOrientation[3]));
- }
- btScalar mass = 0.f;
- if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_MASS)
- {
- mass = clientCmd.m_createBoxShapeArguments.m_mass;
- }
- int shapeType = COLLISION_SHAPE_TYPE_BOX;
- if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE)
- {
- shapeType = clientCmd.m_createBoxShapeArguments.m_collisionShapeType;
- }
- btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld);
- m_data->m_worldImporters.push_back(worldImporter);
- btCollisionShape* shape = 0;
- switch (shapeType)
- {
- case COLLISION_SHAPE_TYPE_CYLINDER_X:
- {
- btScalar radius = halfExtents[1];
- btScalar height = halfExtents[0];
- shape = worldImporter->createCylinderShapeX(radius,height);
- break;
- }
- case COLLISION_SHAPE_TYPE_CYLINDER_Y:
- {
- btScalar radius = halfExtents[0];
- btScalar height = halfExtents[1];
- shape = worldImporter->createCylinderShapeY(radius,height);
- break;
- }
- case COLLISION_SHAPE_TYPE_CYLINDER_Z:
- {
- btScalar radius = halfExtents[1];
- btScalar height = halfExtents[2];
- shape = worldImporter->createCylinderShapeZ(radius,height);
- break;
- }
- case COLLISION_SHAPE_TYPE_CAPSULE_X:
- {
- btScalar radius = halfExtents[1];
- btScalar height = halfExtents[0];
- shape = worldImporter->createCapsuleShapeX(radius,height);
- break;
- }
- case COLLISION_SHAPE_TYPE_CAPSULE_Y:
- {
- btScalar radius = halfExtents[0];
- btScalar height = halfExtents[1];
- shape = worldImporter->createCapsuleShapeY(radius,height);
- break;
- }
- case COLLISION_SHAPE_TYPE_CAPSULE_Z:
- {
- btScalar radius = halfExtents[1];
- btScalar height = halfExtents[2];
- shape = worldImporter->createCapsuleShapeZ(radius,height);
- break;
- }
- case COLLISION_SHAPE_TYPE_SPHERE:
- {
- btScalar radius = halfExtents[0];
- shape = worldImporter->createSphereShape(radius);
- break;
- }
- case COLLISION_SHAPE_TYPE_BOX:
- default:
- {
- shape = worldImporter->createBoxShape(halfExtents);
- }
- }
- bool isDynamic = (mass>0);
- btRigidBody* rb = worldImporter->createRigidBody(isDynamic,mass,startTrans,shape,0);
- //m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld);
- btVector4 colorRGBA(1,0,0,1);
- if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_COLOR)
- {
- colorRGBA[0] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[0];
- colorRGBA[1] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[1];
- colorRGBA[2] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[2];
- colorRGBA[3] = clientCmd.m_createBoxShapeArguments.m_colorRGBA[3];
- }
- m_data->m_guiHelper->createCollisionShapeGraphicsObject(rb->getCollisionShape());
- m_data->m_guiHelper->createCollisionObjectGraphicsObject(rb,colorRGBA);
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_RIGID_BODY_CREATION_COMPLETED;
- int bodyUniqueId = m_data->allocHandle();
- InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId);
- serverCmd.m_rigidBodyCreateArgs.m_bodyUniqueId = bodyUniqueId;
- rb->setUserIndex2(bodyUniqueId);
- bodyHandle->m_rootLocalInertialFrame.setIdentity();
- bodyHandle->m_rigidBody = rb;
- hasStatus = true;
- break;
- }
- case CMD_PICK_BODY:
- {
- pickBody(btVector3(clientCmd.m_pickBodyArguments.m_rayFromWorld[0],
- clientCmd.m_pickBodyArguments.m_rayFromWorld[1],
- clientCmd.m_pickBodyArguments.m_rayFromWorld[2]),
- btVector3(clientCmd.m_pickBodyArguments.m_rayToWorld[0],
- clientCmd.m_pickBodyArguments.m_rayToWorld[1],
- clientCmd.m_pickBodyArguments.m_rayToWorld[2]));
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_MOVE_PICKED_BODY:
- {
- movePickedBody(btVector3(clientCmd.m_pickBodyArguments.m_rayFromWorld[0],
- clientCmd.m_pickBodyArguments.m_rayFromWorld[1],
- clientCmd.m_pickBodyArguments.m_rayFromWorld[2]),
- btVector3(clientCmd.m_pickBodyArguments.m_rayToWorld[0],
- clientCmd.m_pickBodyArguments.m_rayToWorld[1],
- clientCmd.m_pickBodyArguments.m_rayToWorld[2]));
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_REMOVE_PICKING_CONSTRAINT_BODY:
- {
- removePickingConstraint();
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_REQUEST_CONTACT_POINT_INFORMATION:
- {
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_sendContactPointArgs.m_numContactPointsCopied = 0;
-
- //make a snapshot of the contact manifolds into individual contact points
- if (clientCmd.m_requestContactPointArguments.m_startingContactPointIndex==0)
- {
- int numContactManifolds = m_data->m_dynamicsWorld->getDispatcher()->getNumManifolds();
- m_data->m_cachedContactPoints.resize(0);
- m_data->m_cachedContactPoints.reserve(numContactManifolds*4);
- for (int i=0;i<numContactManifolds;i++)
- {
- const btPersistentManifold* manifold = m_data->m_dynamicsWorld->getDispatcher()->getInternalManifoldPointer()[i];
- int linkIndexA = -1;
- int linkIndexB = -1;
-
- int objectIndexB = -1;
- const btRigidBody* bodyB = btRigidBody::upcast(manifold->getBody1());
- if (bodyB)
- {
- objectIndexB = bodyB->getUserIndex2();
- }
- const btMultiBodyLinkCollider* mblB = btMultiBodyLinkCollider::upcast(manifold->getBody1());
- if (mblB && mblB->m_multiBody)
- {
- linkIndexB = mblB->m_link;
- objectIndexB = mblB->m_multiBody->getUserIndex2();
- }
- int objectIndexA = -1;
- const btRigidBody* bodyA = btRigidBody::upcast(manifold->getBody0());
- if (bodyA)
- {
- objectIndexA = bodyA->getUserIndex2();
- }
- const btMultiBodyLinkCollider* mblA = btMultiBodyLinkCollider::upcast(manifold->getBody0());
- if (mblA && mblA->m_multiBody)
- {
- linkIndexA = mblA->m_link;
- objectIndexA = mblA->m_multiBody->getUserIndex2();
- }
- btAssert(bodyA || mblA);
- //apply the filter, if the user provides it
- if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter>=0)
- {
- if ((clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexA) &&
- (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexB))
- continue;
- }
- //apply the second object filter, if the user provides it
- if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter>=0)
- {
- if ((clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexA) &&
- (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB))
- continue;
- }
- for (int p=0;p<manifold->getNumContacts();p++)
- {
- b3ContactPointData pt;
- pt.m_bodyUniqueIdA = objectIndexA;
- pt.m_bodyUniqueIdB = objectIndexB;
- const btManifoldPoint& srcPt = manifold->getContactPoint(p);
- pt.m_contactDistance = srcPt.getDistance();
- pt.m_contactFlags = 0;
- pt.m_linkIndexA = linkIndexA;
- pt.m_linkIndexB = linkIndexB;
- for (int j=0;j<3;j++)
- {
- pt.m_contactNormalOnBInWS[j] = srcPt.m_normalWorldOnB[j];
- pt.m_positionOnAInWS[j] = srcPt.getPositionWorldOnA()[j];
- pt.m_positionOnBInWS[j] = srcPt.getPositionWorldOnB()[j];
- }
- pt.m_normalForce = srcPt.getAppliedImpulse()/m_data->m_physicsDeltaTime;
- // pt.m_linearFrictionForce = srcPt.m_appliedImpulseLateral1;
- m_data->m_cachedContactPoints.push_back (pt);
- }
- }
- }
-
- int numContactPoints = m_data->m_cachedContactPoints.size();
-
- //b3ContactPoint
- //struct b3ContactPointDynamics
- int totalBytesPerContact = sizeof(b3ContactPointData);
- int contactPointStorage = bufferSizeInBytes/totalBytesPerContact-1;
- b3ContactPointData* contactData = (b3ContactPointData*)bufferServerToClient;
- int startContactPointIndex = clientCmd.m_requestContactPointArguments.m_startingContactPointIndex;
- int numContactPointBatch = btMin(numContactPoints,contactPointStorage);
- int endContactPointIndex = startContactPointIndex+numContactPointBatch;
- for (int i=startContactPointIndex;i<endContactPointIndex ;i++)
- {
- const b3ContactPointData& srcPt = m_data->m_cachedContactPoints[i];
- b3ContactPointData& destPt = contactData[serverCmd.m_sendContactPointArgs.m_numContactPointsCopied];
- destPt = srcPt;
- serverCmd.m_sendContactPointArgs.m_numContactPointsCopied++;
- }
-
- serverCmd.m_sendContactPointArgs.m_startingContactPointIndex = clientCmd.m_requestContactPointArguments.m_startingContactPointIndex;
- serverCmd.m_sendContactPointArgs.m_numRemainingContactPoints = numContactPoints - clientCmd.m_requestContactPointArguments.m_startingContactPointIndex - serverCmd.m_sendContactPointArgs.m_numContactPointsCopied;
- serverCmd.m_type = CMD_CONTACT_POINT_INFORMATION_COMPLETED; //CMD_CONTACT_POINT_INFORMATION_FAILED,
- hasStatus = true;
- break;
- }
- case CMD_CALCULATE_INVERSE_DYNAMICS:
- {
- SharedMemoryStatus& serverCmd = serverStatusOut;
- InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateInverseDynamicsArguments.m_bodyUniqueId);
- if (bodyHandle && bodyHandle->m_multiBody)
- {
- serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_FAILED;
-
- btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
- if (tree)
- {
- int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
- const int num_dofs = bodyHandle->m_multiBody->getNumDofs();
- btInverseDynamics::vecx nu(num_dofs+baseDofs), qdot(num_dofs + baseDofs), q(num_dofs + baseDofs), joint_force(num_dofs + baseDofs);
- for (int i = 0; i < num_dofs; i++)
- {
- q[i + baseDofs] = clientCmd.m_calculateInverseDynamicsArguments.m_jointPositionsQ[i];
- qdot[i + baseDofs] = clientCmd.m_calculateInverseDynamicsArguments.m_jointVelocitiesQdot[i];
- nu[i+baseDofs] = clientCmd.m_calculateInverseDynamicsArguments.m_jointAccelerations[i];
- }
- // Set the gravity to correspond to the world gravity
- btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
-
- if (-1 != tree->setGravityInWorldFrame(id_grav) &&
- -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
- {
- serverCmd.m_inverseDynamicsResultArgs.m_bodyUniqueId = clientCmd.m_calculateInverseDynamicsArguments.m_bodyUniqueId;
- serverCmd.m_inverseDynamicsResultArgs.m_dofCount = num_dofs;
- for (int i = 0; i < num_dofs; i++)
- {
- serverCmd.m_inverseDynamicsResultArgs.m_jointForces[i] = joint_force[i+baseDofs];
- }
- serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED;
- }
- else
- {
- serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_FAILED;
- }
- }
- }
- else
- {
- serverCmd.m_type = CMD_CALCULATED_INVERSE_DYNAMICS_FAILED;
- }
- hasStatus = true;
- break;
- }
- case CMD_CALCULATE_JACOBIAN:
- {
- SharedMemoryStatus& serverCmd = serverStatusOut;
- InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateJacobianArguments.m_bodyUniqueId);
- if (bodyHandle && bodyHandle->m_multiBody)
- {
- serverCmd.m_type = CMD_CALCULATED_JACOBIAN_FAILED;
-
- btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
-
- if (tree)
- {
- int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
- const int num_dofs = bodyHandle->m_multiBody->getNumDofs();
- btInverseDynamics::vecx nu(num_dofs+baseDofs), qdot(num_dofs + baseDofs), q(num_dofs + baseDofs), joint_force(num_dofs + baseDofs);
- for (int i = 0; i < num_dofs; i++)
- {
- q[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointPositionsQ[i];
- qdot[i + baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointVelocitiesQdot[i];
- nu[i+baseDofs] = clientCmd.m_calculateJacobianArguments.m_jointAccelerations[i];
- }
- // Set the gravity to correspond to the world gravity
- btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
-
- if (-1 != tree->setGravityInWorldFrame(id_grav) &&
- -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
- {
- serverCmd.m_jacobianResultArgs.m_dofCount = num_dofs;
- // Set jacobian value
- tree->calculateJacobians(q);
- btInverseDynamics::mat3x jac_t(3, num_dofs);
- tree->getBodyJacobianTrans(clientCmd.m_calculateJacobianArguments.m_linkIndex, &jac_t);
- for (int i = 0; i < 3; ++i)
- {
- for (int j = 0; j < num_dofs; ++j)
- {
- serverCmd.m_jacobianResultArgs.m_linearJacobian[i*num_dofs+j] = jac_t(i,j);
- }
- }
- serverCmd.m_type = CMD_CALCULATED_JACOBIAN_COMPLETED;
- }
- else
- {
- serverCmd.m_type = CMD_CALCULATED_JACOBIAN_FAILED;
- }
- }
-
- }
- else
- {
- serverCmd.m_type = CMD_CALCULATED_JACOBIAN_FAILED;
- }
-
- hasStatus = true;
- break;
- }
- case CMD_APPLY_EXTERNAL_FORCE:
- {
- if (m_data->m_verboseOutput)
- {
- b3Printf("CMD_APPLY_EXTERNAL_FORCE clientCmd = %d\n", clientCmd.m_sequenceNumber);
- }
- for (int i = 0; i < clientCmd.m_externalForceArguments.m_numForcesAndTorques; ++i)
- {
- InteralBodyData* body = m_data->getHandle(clientCmd.m_externalForceArguments.m_bodyUniqueIds[i]);
- if (body && body->m_multiBody)
- {
- btMultiBody* mb = body->m_multiBody;
- bool isLinkFrame = ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_LINK_FRAME)!=0);
- if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE)!=0)
- {
- btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0],
- clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+1],
- clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+2]);
- btVector3 positionLocal(
- clientCmd.m_externalForceArguments.m_positions[i*3+0],
- clientCmd.m_externalForceArguments.m_positions[i*3+1],
- clientCmd.m_externalForceArguments.m_positions[i*3+2]);
- if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1)
- {
- btVector3 forceWorld = isLinkFrame ? forceLocal : mb->getBaseWorldTransform().getBasis()*forceLocal;
- btVector3 relPosWorld = isLinkFrame ? positionLocal : mb->getBaseWorldTransform().getBasis()*positionLocal;
- mb->addBaseForce(forceWorld);
- mb->addBaseTorque(relPosWorld.cross(forceWorld));
- //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]);
- } else
- {
- int link = clientCmd.m_externalForceArguments.m_linkIds[i];
- btVector3 forceWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*forceLocal;
- btVector3 relPosWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*positionLocal;
- mb->addLinkForce(link, forceWorld);
- mb->addLinkTorque(link,relPosWorld.cross(forceWorld));
- //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]);
- }
- }
- if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_TORQUE)!=0)
- {
- btVector3 torqueLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0],
- clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+1],
- clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+2]);
- if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1)
- {
- btVector3 torqueWorld = isLinkFrame ? torqueLocal : mb->getBaseWorldTransform().getBasis()*torqueLocal;
- mb->addBaseTorque(torqueWorld);
- //b3Printf("apply base torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]);
- } else
- {
- int link = clientCmd.m_externalForceArguments.m_linkIds[i];
- btVector3 torqueWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*torqueLocal;
- mb->addLinkTorque(link, torqueWorld);
- //b3Printf("apply link torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]);
- }
- }
- }
- }
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_CREATE_JOINT:
- {
- InteralBodyData* parentBody = m_data->getHandle(clientCmd.m_createJointArguments.m_parentBodyIndex);
- if (parentBody && parentBody->m_multiBody)
- {
- InteralBodyData* childBody = m_data->getHandle(clientCmd.m_createJointArguments.m_childBodyIndex);
- if (childBody)
- {
- btVector3 pivotInParent(clientCmd.m_createJointArguments.m_parentFrame[0], clientCmd.m_createJointArguments.m_parentFrame[1], clientCmd.m_createJointArguments.m_parentFrame[2]);
- btVector3 pivotInChild(clientCmd.m_createJointArguments.m_childFrame[0], clientCmd.m_createJointArguments.m_childFrame[1], clientCmd.m_createJointArguments.m_childFrame[2]);
- 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]));
- 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]));
- btVector3 jointAxis(clientCmd.m_createJointArguments.m_jointAxis[0], clientCmd.m_createJointArguments.m_jointAxis[1], clientCmd.m_createJointArguments.m_jointAxis[2]);
- if (clientCmd.m_createJointArguments.m_jointType == eFixedType)
- {
- if (childBody->m_multiBody)
- {
- btMultiBodyFixedConstraint* multibodyFixed = new btMultiBodyFixedConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_multiBody,clientCmd.m_createJointArguments.m_childJointIndex,pivotInParent,pivotInChild,frameInParent,frameInChild);
- multibodyFixed->setMaxAppliedImpulse(500.0);
- m_data->m_dynamicsWorld->addMultiBodyConstraint(multibodyFixed);
- }
- else
- {
- btMultiBodyFixedConstraint* rigidbodyFixed = new btMultiBodyFixedConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_rigidBody,pivotInParent,pivotInChild,frameInParent,frameInChild);
- rigidbodyFixed->setMaxAppliedImpulse(500.0);
- btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
- world->addMultiBodyConstraint(rigidbodyFixed);
- }
- }
- else if (clientCmd.m_createJointArguments.m_jointType == ePrismaticType)
- {
- if (childBody->m_multiBody)
- {
- 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);
- multibodySlider->setMaxAppliedImpulse(500.0);
- m_data->m_dynamicsWorld->addMultiBodyConstraint(multibodySlider);
- }
- else
- {
- btMultiBodySliderConstraint* rigidbodySlider = new btMultiBodySliderConstraint(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_rigidBody,pivotInParent,pivotInChild,frameInParent,frameInChild,jointAxis);
- rigidbodySlider->setMaxAppliedImpulse(500.0);
- btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
- world->addMultiBodyConstraint(rigidbodySlider);
- }
- } else if (clientCmd.m_createJointArguments.m_jointType == ePoint2PointType)
- {
- if (childBody->m_multiBody)
- {
- btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_multiBody,clientCmd.m_createJointArguments.m_childJointIndex,pivotInParent,pivotInChild);
- p2p->setMaxAppliedImpulse(500);
- m_data->m_dynamicsWorld->addMultiBodyConstraint(p2p);
- }
- else
- {
- btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(parentBody->m_multiBody,clientCmd.m_createJointArguments.m_parentJointIndex,childBody->m_rigidBody,pivotInParent,pivotInChild);
- p2p->setMaxAppliedImpulse(500);
- btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
- world->addMultiBodyConstraint(p2p);
- }
- }
- }
- }
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED;
- hasStatus = true;
- break;
- }
- case CMD_CALCULATE_INVERSE_KINEMATICS:
- {
- SharedMemoryStatus& serverCmd = serverStatusOut;
- serverCmd.m_type = CMD_CALCULATE_INVERSE_KINEMATICS_FAILED;
- InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateInverseKinematicsArguments.m_bodyUniqueId);
- if (bodyHandle && bodyHandle->m_multiBody)
- {
- IKTrajectoryHelper** ikHelperPtrPtr = m_data->m_inverseKinematicsHelpers.find(bodyHandle->m_multiBody);
- IKTrajectoryHelper* ikHelperPtr = 0;
-
- if (ikHelperPtrPtr)
- {
- ikHelperPtr = *ikHelperPtrPtr;
- }
- else
- {
- IKTrajectoryHelper* tmpHelper = new IKTrajectoryHelper;
- m_data->m_inverseKinematicsHelpers.insert(bodyHandle->m_multiBody, tmpHelper);
- ikHelperPtr = tmpHelper;
- }
- int endEffectorLinkIndex = clientCmd.m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex;
-
-
- if (ikHelperPtr && (endEffectorLinkIndex<bodyHandle->m_multiBody->getNumLinks()))
- {
- const int numDofs = bodyHandle->m_multiBody->getNumDofs();
- b3AlignedObjectArray<double> jacobian_linear;
- jacobian_linear.resize(3*numDofs);
- b3AlignedObjectArray<double> jacobian_angular;
- jacobian_angular.resize(3*numDofs);
- int jacSize = 0;
-
- btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
-
-
- btAlignedObjectArray<double> q_current;
- q_current.resize(numDofs);
-
- if (tree)
- {
- jacSize = jacobian_linear.size();
- // Set jacobian value
- int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
-
-
- btInverseDynamics::vecx nu(numDofs+baseDofs), qdot(numDofs + baseDofs), q(numDofs + baseDofs), joint_force(numDofs + baseDofs);
- for (int i = 0; i < numDofs; i++)
- {
- q_current[i] = bodyHandle->m_multiBody->getJointPos(i);
- q[i+baseDofs] = bodyHandle->m_multiBody->getJointPos(i);
- qdot[i + baseDofs] = 0;
- nu[i+baseDofs] = 0;
- }
- // Set the gravity to correspond to the world gravity
- btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
-
- if (-1 != tree->setGravityInWorldFrame(id_grav) &&
- -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
- {
- tree->calculateJacobians(q);
- btInverseDynamics::mat3x jac_t(3, numDofs);
- btInverseDynamics::mat3x jac_r(3,numDofs);
- tree->getBodyJacobianTrans(endEffectorLinkIndex, &jac_t);
- tree->getBodyJacobianRot(endEffectorLinkIndex, &jac_r);
- for (int i = 0; i < 3; ++i)
- {
- for (int j = 0; j < numDofs; ++j)
- {
- jacobian_linear[i*numDofs+j] = jac_t(i,j);
- jacobian_angular[i*numDofs+j] = jac_r(i,j);
- }
- }
- }
- }
-
-
- btAlignedObjectArray<double> q_new;
- q_new.resize(numDofs);
- int ikMethod = 0;
- if ((clientCmd.m_updateFlags& IK_HAS_TARGET_ORIENTATION)&&(clientCmd.m_updateFlags&IK_HAS_NULL_SPACE_VELOCITY))
- {
- ikMethod = IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE;
- }
- else if (clientCmd.m_updateFlags& IK_HAS_TARGET_ORIENTATION)
- {
- ikMethod = IK2_VEL_DLS_WITH_ORIENTATION;
- }
- else if (clientCmd.m_updateFlags& IK_HAS_NULL_SPACE_VELOCITY)
- {
- ikMethod = IK2_VEL_DLS_WITH_NULLSPACE;
- }
- else
- {
- ikMethod = IK2_VEL_DLS;
- }
-
- if (clientCmd.m_updateFlags& IK_HAS_NULL_SPACE_VELOCITY)
- {
- btAlignedObjectArray<double> lower_limit;
- btAlignedObjectArray<double> upper_limit;
- btAlignedObjectArray<double> joint_range;
- btAlignedObjectArray<double> rest_pose;
- lower_limit.resize(numDofs);
- upper_limit.resize(numDofs);
- joint_range.resize(numDofs);
- rest_pose.resize(numDofs);
- for (int i = 0; i < numDofs; ++i)
- {
- lower_limit[i] = clientCmd.m_calculateInverseKinematicsArguments.m_lowerLimit[i];
- upper_limit[i] = clientCmd.m_calculateInverseKinematicsArguments.m_upperLimit[i];
- joint_range[i] = clientCmd.m_calculateInverseKinematicsArguments.m_jointRange[i];
- rest_pose[i] = clientCmd.m_calculateInverseKinematicsArguments.m_restPose[i];
- }
- ikHelperPtr->computeNullspaceVel(numDofs, &q_current[0], &lower_limit[0], &upper_limit[0], &joint_range[0], &rest_pose[0]);
- }
-
- btTransform endEffectorTransformWorld = bodyHandle->m_multiBody->getLink(endEffectorLinkIndex).m_cachedWorldTransform * bodyHandle->m_linkLocalInertialFrames[endEffectorLinkIndex].inverse();
-
- btVector3DoubleData endEffectorWorldPosition;
- btVector3DoubleData endEffectorWorldOrientation;
-
- btVector3 endEffectorPosWorld = endEffectorTransformWorld.getOrigin();
- btQuaternion endEffectorOriWorld = endEffectorTransformWorld.getRotation();
- btVector4 endEffectorOri(endEffectorOriWorld.x(),endEffectorOriWorld.y(),endEffectorOriWorld.z(),endEffectorOriWorld.w());
-
- endEffectorPosWorld.serializeDouble(endEffectorWorldPosition);
- endEffectorOri.serializeDouble(endEffectorWorldOrientation);
- double dampIK[6] = { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 };
- ikHelperPtr->computeIK(clientCmd.m_calculateInverseKinematicsArguments.m_targetPosition, clientCmd.m_calculateInverseKinematicsArguments.m_targetOrientation,
- endEffectorWorldPosition.m_floats, endEffectorWorldOrientation.m_floats,
- &q_current[0],
- numDofs, clientCmd.m_calculateInverseKinematicsArguments.m_endEffectorLinkIndex,
- &q_new[0], ikMethod, &jacobian_linear[0], &jacobian_angular[0], jacSize*2, dampIK);
-
- serverCmd.m_inverseKinematicsResultArgs.m_bodyUniqueId =clientCmd.m_calculateInverseDynamicsArguments.m_bodyUniqueId;
- for (int i=0;i<numDofs;i++)
- {
- serverCmd.m_inverseKinematicsResultArgs.m_jointPositions[i] = q_new[i];
- }
- serverCmd.m_inverseKinematicsResultArgs.m_dofCount = numDofs;
- serverCmd.m_type = CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED;
- }
- }
- hasStatus = true;
- break;
- }
-
- default:
- {
- b3Error("Unknown command encountered");
- SharedMemoryStatus& serverCmd =serverStatusOut;
- serverCmd.m_type = CMD_UNKNOWN_COMMAND_FLUSHED;
- hasStatus = true;
- }
- };
- }
- }
- return hasStatus;
- }
- static int skip=1;
- void PhysicsServerCommandProcessor::renderScene()
- {
- if (m_data->m_guiHelper)
- {
- m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld);
- m_data->m_guiHelper->render(m_data->m_dynamicsWorld);
- }
- }
- void PhysicsServerCommandProcessor::physicsDebugDraw(int debugDrawFlags)
- {
- if (m_data->m_dynamicsWorld)
- {
- if (m_data->m_dynamicsWorld->getDebugDrawer())
- {
- m_data->m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugDrawFlags);
- m_data->m_dynamicsWorld->debugDrawWorld();
- }
- }
- }
- bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
- {
- if (m_data->m_dynamicsWorld==0)
- return false;
- btCollisionWorld::ClosestRayResultCallback rayCallback(rayFromWorld, rayToWorld);
- m_data->m_dynamicsWorld->rayTest(rayFromWorld, rayToWorld, rayCallback);
- if (rayCallback.hasHit())
- {
- btVector3 pickPos = rayCallback.m_hitPointWorld;
- gLastPickPos = pickPos;
- btRigidBody* body = (btRigidBody*)btRigidBody::upcast(rayCallback.m_collisionObject);
- if (body)
- {
- //other exclusions?
- if (!(body->isStaticObject() || body->isKinematicObject()))
- {
- m_data->m_pickedBody = body;
- m_data->m_pickedBody->setActivationState(DISABLE_DEACTIVATION);
- //printf("pickPos=%f,%f,%f\n",pickPos.getX(),pickPos.getY(),pickPos.getZ());
- btVector3 localPivot = body->getCenterOfMassTransform().inverse() * pickPos;
- btPoint2PointConstraint* p2p = new btPoint2PointConstraint(*body, localPivot);
- m_data->m_dynamicsWorld->addConstraint(p2p, true);
- m_data->m_pickedConstraint = p2p;
- btScalar mousePickClamping = 30.f;
- p2p->m_setting.m_impulseClamp = mousePickClamping;
- //very weak constraint for picking
- p2p->m_setting.m_tau = 0.001f;
- }
-
- } else
- {
- btMultiBodyLinkCollider* multiCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(rayCallback.m_collisionObject);
- if (multiCol && multiCol->m_multiBody)
- {
- m_data->m_prevCanSleep = multiCol->m_multiBody->getCanSleep();
- multiCol->m_multiBody->setCanSleep(false);
- btVector3 pivotInA = multiCol->m_multiBody->worldPosToLocal(multiCol->m_link, pickPos);
- btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(multiCol->m_multiBody,multiCol->m_link,0,pivotInA,pickPos);
- //if you add too much energy to the system, causing high angular velocities, simulation 'explodes'
- //see also http://www.bulletphysics.org/Bullet/phpBB3/viewtopic.php?f=4&t=949
- //so we try to avoid it by clamping the maximum impulse (force) that the mouse pick can apply
- //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?)
- btScalar scaling=1;
- p2p->setMaxAppliedImpulse(2*scaling);
- btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
- world->addMultiBodyConstraint(p2p);
- m_data->m_pickingMultiBodyPoint2Point =p2p;
- }
- }
- // pickObject(pickPos, rayCallback.m_collisionObject);
- m_data->m_oldPickingPos = rayToWorld;
- m_data->m_hitPos = pickPos;
- m_data->m_oldPickingDist = (pickPos - rayFromWorld).length();
- // printf("hit !\n");
- //add p2p
- }
- return false;
- }
- bool PhysicsServerCommandProcessor::movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
- {
- if (m_data->m_pickedBody && m_data->m_pickedConstraint)
- {
- btPoint2PointConstraint* pickCon = static_cast<btPoint2PointConstraint*>(m_data->m_pickedConstraint);
- if (pickCon)
- {
- //keep it at the same picking distance
- btVector3 dir = rayToWorld-rayFromWorld;
- dir.normalize();
- dir *= m_data->m_oldPickingDist;
- btVector3 newPivotB = rayFromWorld + dir;
- pickCon->setPivotB(newPivotB);
- }
- }
- if (m_data->m_pickingMultiBodyPoint2Point)
- {
- //keep it at the same picking distance
- btVector3 dir = rayToWorld-rayFromWorld;
- dir.normalize();
- dir *= m_data->m_oldPickingDist;
- btVector3 newPivotB = rayFromWorld + dir;
- m_data->m_pickingMultiBodyPoint2Point->setPivotInB(newPivotB);
- }
- return false;
- }
- void PhysicsServerCommandProcessor::removePickingConstraint()
- {
- if (m_data->m_pickedConstraint)
- {
- m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint);
- delete m_data->m_pickedConstraint;
- m_data->m_pickedConstraint = 0;
- m_data->m_pickedBody->forceActivationState(ACTIVE_TAG);
- m_data->m_pickedBody = 0;
- }
- if (m_data->m_pickingMultiBodyPoint2Point)
- {
- m_data->m_pickingMultiBodyPoint2Point->getMultiBodyA()->setCanSleep(m_data->m_prevCanSleep);
- btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld;
- world->removeMultiBodyConstraint(m_data->m_pickingMultiBodyPoint2Point);
- delete m_data->m_pickingMultiBodyPoint2Point;
- m_data->m_pickingMultiBodyPoint2Point = 0;
- }
- }
- void PhysicsServerCommandProcessor::enableCommandLogging(bool enable, const char* fileName)
- {
- if (enable)
- {
- if (0==m_data->m_commandLogger)
- {
- m_data->m_commandLogger = new CommandLogger(fileName);
- }
- } else
- {
- if (0!=m_data->m_commandLogger)
- {
- delete m_data->m_commandLogger;
- m_data->m_commandLogger = 0;
- }
- }
- }
- void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
- {
- CommandLogPlayback* pb = new CommandLogPlayback(fileName);
- m_data->m_logPlayback = pb;
- }
- btVector3 gVRGripperPos(0,0,0.2);
- btQuaternion gVRGripperOrn(0,0,0,1);
- btVector3 gVRController2Pos(0,0,0.2);
- btQuaternion gVRController2Orn(0,0,0,1);
- btScalar gVRGripper2Analog = 0;
- btScalar gVRGripperAnalog = 0;
- bool gVRGripperClosed = false;
- int gDroppedSimulationSteps = 0;
- int gNumSteps = 0;
- double gDtInSec = 0.f;
- double gSubStep = 0.f;
- void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
- {
- if ((gEnableRealTimeSimVR || m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
- {
- static btAlignedObjectArray<char> gBufferServerToClient;
- gBufferServerToClient.resize(SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
- int bodyId = 0;
-
- if (gCreateObjectSimVR >= 0)
- {
- gCreateObjectSimVR = -1;
- btMatrix3x3 mat(gVRGripperOrn);
- btScalar spawnDistance = 0.1;
- btVector3 spawnDir = mat.getColumn(0);
- btVector3 shiftPos = spawnDir*spawnDistance;
- btVector3 spawnPos = gVRGripperPos + shiftPos;
- loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //loadUrdf("lego/lego.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- m_data->m_sphereId = bodyId;
- InteralBodyData* parentBody = m_data->getHandle(bodyId);
- if (parentBody->m_multiBody)
- {
- parentBody->m_multiBody->setBaseVel(spawnDir * 5);
- }
- }
- ///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
- if (gCreateSamuraiRobotAssets)
- {
- if (!m_data->m_hasGround)
- {
- m_data->m_hasGround = true;
- loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("samurai.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- if (m_data->m_gripperRigidbodyFixed == 0)
- {
- int bodyId = 0;
- if (loadUrdf("pr2_gripper.urdf", btVector3(0, 0, 0.1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()))
- {
- InteralBodyData* parentBody = m_data->getHandle(bodyId);
- if (parentBody->m_multiBody)
- {
- parentBody->m_multiBody->setHasSelfCollision(0);
- btVector3 pivotInParent(0.2, 0, 0);
- btMatrix3x3 frameInParent;
- //frameInParent.setRotation(btQuaternion(0, 0, 0, 1));
- frameInParent.setIdentity();
- btVector3 pivotInChild(0, 0, 0);
- btMatrix3x3 frameInChild;
- frameInChild.setIdentity();
- m_data->m_gripperRigidbodyFixed = new btMultiBodyFixedConstraint(parentBody->m_multiBody, -1, 0, pivotInParent, pivotInChild, frameInParent, frameInChild);
- m_data->m_gripperMultiBody = parentBody->m_multiBody;
- if (m_data->m_gripperMultiBody->getNumLinks() > 2)
- {
- m_data->m_gripperMultiBody->setJointPos(0, 0);
- m_data->m_gripperMultiBody->setJointPos(2, 0);
- }
- m_data->m_gripperRigidbodyFixed->setMaxAppliedImpulse(500);
- btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*)m_data->m_dynamicsWorld;
- world->addMultiBodyConstraint(m_data->m_gripperRigidbodyFixed);
- }
- }
- }
- 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());
- m_data->m_KukaId = bodyId;
- loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .7), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .8), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .9), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("r2d2.urdf", btVector3(-2, -4, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- // Load one motor gripper for kuka
- loadSdf("gripper/wsg50_one_motor_gripper_new_free_base.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
- m_data->m_gripperId = bodyId + 1;
- InteralBodyData* kukaBody = m_data->getHandle(m_data->m_KukaId);
- InteralBodyData* gripperBody = m_data->getHandle(m_data->m_gripperId);
- // Reset the default gripper motor maximum torque for damping to 0
- for (int i = 0; i < gripperBody->m_multiBody->getNumLinks(); i++)
- {
- if (supportsJointMotor(gripperBody->m_multiBody, i))
- {
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)gripperBody->m_multiBody->getLink(i).m_userPtr;
- if (motor)
- {
- motor->setMaxAppliedImpulse(0);
- }
- }
- }
-
- for (int i = 0; i < 6; i++)
- {
- 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());
- }
- //loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- // Add slider joint for fingers
- btVector3 pivotInParent1(-0.055, 0, 0.02);
- btVector3 pivotInChild1(0, 0, 0);
- btMatrix3x3 frameInParent1(btQuaternion(0, 0, 0, 1.0));
- btMatrix3x3 frameInChild1(btQuaternion(0, 0, 0, 1.0));
- btVector3 jointAxis1(1.0, 0, 0);
- btVector3 pivotInParent2(0.055, 0, 0.02);
- btVector3 pivotInChild2(0, 0, 0);
- btMatrix3x3 frameInParent2(btQuaternion(0, 0, 0, 1.0));
- btMatrix3x3 frameInChild2(btQuaternion(0, 0, 1.0, 0));
- btVector3 jointAxis2(1.0, 0, 0);
- m_data->m_kukaGripperRevolute1 = new btMultiBodyPoint2Point(gripperBody->m_multiBody, 2, gripperBody->m_multiBody, 4, pivotInParent1, pivotInChild1);
- m_data->m_kukaGripperRevolute1->setMaxAppliedImpulse(5.0);
- m_data->m_kukaGripperRevolute2 = new btMultiBodyPoint2Point(gripperBody->m_multiBody, 3, gripperBody->m_multiBody, 6, pivotInParent2, pivotInChild2);
- m_data->m_kukaGripperRevolute2->setMaxAppliedImpulse(5.0);
- m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperRevolute1);
- m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperRevolute2);
- if (kukaBody->m_multiBody && kukaBody->m_multiBody->getNumDofs()==7)
- {
- gripperBody->m_multiBody->setHasSelfCollision(0);
- btVector3 pivotInParent(0, 0, 0.05);
- btMatrix3x3 frameInParent;
- frameInParent.setIdentity();
- btVector3 pivotInChild(0, 0, 0);
- btMatrix3x3 frameInChild;
- frameInChild.setIdentity();
- m_data->m_kukaGripperFixed = new btMultiBodyFixedConstraint(kukaBody->m_multiBody, 6, gripperBody->m_multiBody, 0, pivotInParent, pivotInChild, frameInParent, frameInChild);
- m_data->m_kukaGripperMultiBody = gripperBody->m_multiBody;
- m_data->m_kukaGripperFixed->setMaxAppliedImpulse(500);
- m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperFixed);
- }
- for (int i = 0; i < 10; i++)
- {
- loadUrdf("cube.urdf", btVector3(-4, -2, 0.5 + i), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- }
- loadUrdf("sphere2.urdf", btVector3(-5, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("sphere2.urdf", btVector3(-5, 0, 2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("sphere2.urdf", btVector3(-5, 0, 3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
-
- btTransform objectLocalTr[] = {
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.0, 0.0, 0.0)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.0, 0.15, 0.64)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.1, 0.15, 0.85)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.4, 0.05, 0.85)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.3, -0.05, 0.7)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.1, 0.05, 0.7)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.2, 0.15, 0.7)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.2, 0.15, 0.9)),
- btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.2, 0.05, 0.8))
- };
- btAlignedObjectArray<btTransform> objectWorldTr;
- int numOb = sizeof(objectLocalTr) / sizeof(btTransform);
- objectWorldTr.resize(numOb);
- btTransform tr;
- tr.setIdentity();
- tr.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI));
- tr.setOrigin(btVector3(1.0, -0.2, 0));
- for (int i = 0; i < numOb; i++)
- {
- objectWorldTr[i] = tr*objectLocalTr[i];
- }
- // Table area
- loadUrdf("table/table.urdf", objectWorldTr[0].getOrigin(), objectWorldTr[0].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("tray.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //loadUrdf("cup_small.urdf", objectWorldTr[2].getOrigin(), objectWorldTr[2].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //loadUrdf("pitcher_small.urdf", objectWorldTr[3].getOrigin(), objectWorldTr[3].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("teddy_vhacd.urdf", objectWorldTr[4].getOrigin(), objectWorldTr[4].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("cube_small.urdf", objectWorldTr[5].getOrigin(), objectWorldTr[5].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("sphere_small.urdf", objectWorldTr[6].getOrigin(), objectWorldTr[6].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("duck_vhacd.urdf", objectWorldTr[7].getOrigin(), objectWorldTr[7].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //loadUrdf("Apple/apple.urdf", objectWorldTr[8].getOrigin(), objectWorldTr[8].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- // Shelf area
- loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
- loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- loadUrdf("cube_small.urdf", btVector3(0.3, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
-
- // Chess area
- loadUrdf("table_square/table_square.urdf", btVector3(-1.0, 0, 0.0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //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());
- //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());
- //loadUrdf("king.urdf", btVector3(-1.0, 0, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //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());
- //loadUrdf("rook.urdf", btVector3(-1.2, 0, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- //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());
- //loadUrdf("husky/husky.urdf", btVector3(2, -5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
- m_data->m_huskyId = bodyId;
- m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
- }
- if (m_data->m_kukaGripperFixed && m_data->m_kukaGripperMultiBody)
- {
- InteralBodyData* childBody = m_data->getHandle(m_data->m_gripperId);
- // Add gripper controller
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)childBody->m_multiBody->getLink(1).m_userPtr;
- if (motor)
- {
- btScalar posTarget = (-0.048)*btMin(btScalar(0.75), gVRGripper2Analog) / 0.75;
- motor->setPositionTarget(posTarget, .2);
- motor->setVelocityTarget(0.0, .5);
- motor->setMaxAppliedImpulse(5.0);
- }
- }
- if (m_data->m_gripperRigidbodyFixed && m_data->m_gripperMultiBody)
- {
- m_data->m_gripperRigidbodyFixed->setFrameInB(btMatrix3x3(gVRGripperOrn));
- m_data->m_gripperRigidbodyFixed->setPivotInB(gVRGripperPos);
- for (int i = 0; i < m_data->m_gripperMultiBody->getNumLinks(); i++)
- {
- if (supportsJointMotor(m_data->m_gripperMultiBody, i))
- {
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)m_data->m_gripperMultiBody->getLink(i ).m_userPtr;
- if (motor)
- {
- motor->setErp(0.2);
- btScalar posTarget = 0.1 + (1 - btMin(btScalar(0.75),gVRGripperAnalog)*btScalar(1.5))*SIMD_HALF_PI*0.29;
- btScalar maxPosTarget = 0.55;
-
- if (m_data->m_gripperMultiBody->getJointPos(i) < 0)
- {
- m_data->m_gripperMultiBody->setJointPos(i,0);
- }
- if (m_data->m_gripperMultiBody->getJointPos(i) > maxPosTarget)
- {
- m_data->m_gripperMultiBody->setJointPos(i, maxPosTarget);
- }
- motor->setPositionTarget(posTarget, 1);
- motor->setVelocityTarget(0, 0.5);
- btScalar maxImp = 1*m_data->m_physicsDeltaTime;
- motor->setMaxAppliedImpulse(maxImp);
- //motor->setRhsClamp(gRhsClamp);
- }
- }
- }
- }
- // Inverse kinematics for KUKA
- //if (0)
- {
- InternalBodyHandle* bodyHandle = m_data->getHandle(m_data->m_KukaId);
- if (bodyHandle && bodyHandle->m_multiBody && bodyHandle->m_multiBody->getNumDofs()==7)
- {
- btMultiBody* mb = bodyHandle->m_multiBody;
- btScalar sqLen = (mb->getBaseWorldTransform().getOrigin() - gVRController2Pos).length2();
- btScalar distanceThreshold = 1.3;
- gCloseToKuka=(sqLen<(distanceThreshold*distanceThreshold));
- int numDofs = bodyHandle->m_multiBody->getNumDofs();
- btAlignedObjectArray<double> q_new;
- btAlignedObjectArray<double> q_current;
- q_current.resize(numDofs);
- for (int i = 0; i < numDofs; i++)
- {
- q_current[i] = bodyHandle->m_multiBody->getJointPos(i);
- }
-
- q_new.resize(numDofs);
- //sensible rest-pose
- q_new[0] = 0;// -SIMD_HALF_PI;
- q_new[1] = 0;
- q_new[2] = 0;
- q_new[3] = SIMD_HALF_PI;
- q_new[4] = 0;
- q_new[5] = -SIMD_HALF_PI*0.66;
- q_new[6] = 0;
- if (gCloseToKuka)
- {
- double dampIk[6] = {1.0, 1.0, 1.0, 1.0, 1.0, 0.0};
- IKTrajectoryHelper** ikHelperPtrPtr = m_data->m_inverseKinematicsHelpers.find(bodyHandle->m_multiBody);
- IKTrajectoryHelper* ikHelperPtr = 0;
- if (ikHelperPtrPtr)
- {
- ikHelperPtr = *ikHelperPtrPtr;
- }
- else
- {
- IKTrajectoryHelper* tmpHelper = new IKTrajectoryHelper;
- m_data->m_inverseKinematicsHelpers.insert(bodyHandle->m_multiBody, tmpHelper);
- ikHelperPtr = tmpHelper;
- }
- int endEffectorLinkIndex = 6;
- if (ikHelperPtr && (endEffectorLinkIndex<bodyHandle->m_multiBody->getNumLinks()))
- {
- b3AlignedObjectArray<double> jacobian_linear;
- jacobian_linear.resize(3*numDofs);
- b3AlignedObjectArray<double> jacobian_angular;
- jacobian_angular.resize(3*numDofs);
- int jacSize = 0;
-
- btInverseDynamics::MultiBodyTree* tree = m_data->findOrCreateTree(bodyHandle->m_multiBody);
-
- if (tree)
- {
- jacSize = jacobian_linear.size();
- // Set jacobian value
- int baseDofs = bodyHandle->m_multiBody->hasFixedBase() ? 0 : 6;
-
- btInverseDynamics::vecx nu(numDofs+baseDofs), qdot(numDofs + baseDofs), q(numDofs + baseDofs), joint_force(numDofs + baseDofs);
- for (int i = 0; i < numDofs; i++)
- {
- q_current[i] = bodyHandle->m_multiBody->getJointPos(i);
- q[i+baseDofs] = bodyHandle->m_multiBody->getJointPos(i);
- qdot[i + baseDofs] = 0;
- nu[i+baseDofs] = 0;
- }
- // Set the gravity to correspond to the world gravity
- btInverseDynamics::vec3 id_grav(m_data->m_dynamicsWorld->getGravity());
-
- if (-1 != tree->setGravityInWorldFrame(id_grav) &&
- -1 != tree->calculateInverseDynamics(q, qdot, nu, &joint_force))
- {
- tree->calculateJacobians(q);
- btInverseDynamics::mat3x jac_t(3,numDofs);
- btInverseDynamics::mat3x jac_r(3,numDofs);
- tree->getBodyJacobianTrans(endEffectorLinkIndex, &jac_t);
- tree->getBodyJacobianRot(endEffectorLinkIndex, &jac_r);
- for (int i = 0; i < 3; ++i)
- {
- for (int j = 0; j < numDofs; ++j)
- {
- jacobian_linear[i*numDofs+j] = jac_t(i,j);
- jacobian_angular[i*numDofs+j] = jac_r(i,j);
- }
- }
- }
- }
-
- int ikMethod= IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE;//IK2_VEL_DLS_WITH_ORIENTATION; //IK2_VEL_DLS;
-
- btVector3DoubleData endEffectorWorldPosition;
- btVector3DoubleData endEffectorWorldOrientation;
- btVector3DoubleData targetWorldPosition;
- btVector3DoubleData targetWorldOrientation;
-
- btVector3 endEffectorPosWorld = bodyHandle->m_multiBody->getLink(endEffectorLinkIndex).m_cachedWorldTransform.getOrigin();
- btQuaternion endEffectorOriWorld = bodyHandle->m_multiBody->getLink(endEffectorLinkIndex).m_cachedWorldTransform.getRotation();
- btVector4 endEffectorOri(endEffectorOriWorld.x(),endEffectorOriWorld.y(),endEffectorOriWorld.z(),endEffectorOriWorld.w());
-
- // Prescribed position and orientation
- static btScalar time=0.f;
- time+=0.01;
- btVector3 targetPos(0.4-0.4*b3Cos( time), 0, 0.8+0.4*b3Cos( time));
- targetPos +=mb->getBasePos();
- btVector4 downOrn(0,1,0,0);
- // Controller orientation
- btVector4 controllerOrn(gVRController2Orn.x(), gVRController2Orn.y(), gVRController2Orn.z(), gVRController2Orn.w());
-
- // Set position and orientation
- endEffectorPosWorld.serializeDouble(endEffectorWorldPosition);
- endEffectorOri.serializeDouble(endEffectorWorldOrientation);
- downOrn.serializeDouble(targetWorldOrientation);
- //targetPos.serializeDouble(targetWorldPosition);
-
- gVRController2Pos.serializeDouble(targetWorldPosition);
-
- //controllerOrn.serializeDouble(targetWorldOrientation);
- if (ikMethod == IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE)
- {
- btAlignedObjectArray<double> lower_limit;
- btAlignedObjectArray<double> upper_limit;
- btAlignedObjectArray<double> joint_range;
- btAlignedObjectArray<double> rest_pose;
- lower_limit.resize(numDofs);
- upper_limit.resize(numDofs);
- joint_range.resize(numDofs);
- rest_pose.resize(numDofs);
- lower_limit[0] = -.967;
- lower_limit[1] = -2.0;
- lower_limit[2] = -2.96;
- lower_limit[3] = 0.19;
- lower_limit[4] = -2.96;
- lower_limit[5] = -2.09;
- lower_limit[6] = -3.05;
- upper_limit[0] = .96;
- upper_limit[1] = 2.0;
- upper_limit[2] = 2.96;
- upper_limit[3] = 2.29;
- upper_limit[4] = 2.96;
- upper_limit[5] = 2.09;
- upper_limit[6] = 3.05;
- joint_range[0] = 5.8;
- joint_range[1] = 4;
- joint_range[2] = 5.8;
- joint_range[3] = 4;
- joint_range[4] = 5.8;
- joint_range[5] = 4;
- joint_range[6] = 6;
- rest_pose[0] = 0;
- rest_pose[1] = 0;
- rest_pose[2] = 0;
- rest_pose[3] = SIMD_HALF_PI;
- rest_pose[4] = 0;
- rest_pose[5] = -SIMD_HALF_PI*0.66;
- rest_pose[6] = 0;
- ikHelperPtr->computeNullspaceVel(numDofs, &q_current[0], &lower_limit[0], &upper_limit[0], &joint_range[0], &rest_pose[0]);
- }
- ikHelperPtr->computeIK(targetWorldPosition.m_floats, targetWorldOrientation.m_floats,
- endEffectorWorldPosition.m_floats, endEffectorWorldOrientation.m_floats,
- &q_current[0],
- numDofs, endEffectorLinkIndex,
- &q_new[0], ikMethod, &jacobian_linear[0], &jacobian_angular[0], jacSize*2, dampIk);
- }
- }
- //directly set the position of the links, only for debugging IK, don't use this method!
- if (0)
- {
- for (int i=0;i<mb->getNumLinks();i++)
- {
- btScalar desiredPosition = q_new[i];
- mb->setJointPosMultiDof(i,&desiredPosition);
- }
- } else
- {
- int numMotors = 0;
- //find the joint motors and apply the desired velocity and maximum force/torque
- {
- int velIndex = 6;//skip the 3 linear + 3 angular degree of freedom velocity entries of the base
- int posIndex = 7;//skip 3 positional and 4 orientation (quaternion) positional degrees of freedom of the base
- for (int link=0;link<mb->getNumLinks();link++)
- {
- if (supportsJointMotor(mb,link))
- {
- btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr;
- if (motor)
- {
- btScalar desiredVelocity = 0.f;
- btScalar desiredPosition = q_new[link];
- motor->setRhsClamp(gRhsClamp);
- //printf("link %d: %f", link, q_new[link]);
- motor->setVelocityTarget(desiredVelocity,1.0);
- motor->setPositionTarget(desiredPosition,0.6);
- btScalar maxImp = 1.0;
-
- motor->setMaxAppliedImpulse(maxImp);
- numMotors++;
- }
- }
- velIndex += mb->getLink(link).m_dofCount;
- posIndex += mb->getLink(link).m_posVarCount;
- }
- }
- }
- }
-
- }
- }
- int maxSteps = m_data->m_numSimulationSubSteps+3;
- if (m_data->m_numSimulationSubSteps)
- {
- gSubStep = m_data->m_physicsDeltaTime / m_data->m_numSimulationSubSteps;
- }
- else
- {
- gSubStep = m_data->m_physicsDeltaTime;
- }
-
- int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);
- gDroppedSimulationSteps += numSteps > maxSteps ? numSteps - maxSteps : 0;
- if (numSteps)
- {
- gNumSteps = numSteps;
- gDtInSec = dtInSec;
- }
- }
- }
- void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
- {
- InteralBodyData* body = m_data->getHandle(bodyUniqueId);
- if (body) {
- btMultiBody* mb = body->m_multiBody;
- if (mb) {
- for (int l=0;l<mb->getNumLinks();l++) {
- for (int d=0;d<mb->getLink(l).m_dofCount;d++) {
- double damping_coefficient = mb->getLink(l).m_jointDamping;
- double damping = -damping_coefficient*mb->getJointVelMultiDof(l)[d];
- mb->addJointTorqueMultiDof(l, d, damping);
- }
- }
- }
- }
- }
|