InverseDynamicsExample.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368
  1. /*
  2. Bullet Continuous Collision Detection and Physics Library
  3. Copyright (c) 2015 Google Inc. http://bulletphysics.org
  4. This software is provided 'as-is', without any express or implied warranty.
  5. In no event will the authors be held liable for any damages arising from the use of this software.
  6. Permission is granted to anyone to use this software for any purpose,
  7. including commercial applications, and to alter it and redistribute it freely,
  8. subject to the following restrictions:
  9. 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
  10. 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
  11. 3. This notice may not be removed or altered from any source distribution.
  12. */
  13. #include "InverseDynamicsExample.h"
  14. #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
  15. #include "Bullet3Common/b3FileUtils.h"
  16. #include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
  17. #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
  18. #include "../CommonInterfaces/CommonParameterInterface.h"
  19. #include "../Utils/b3ResourcePath.h"
  20. #include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
  21. #include "../Importers/ImportURDFDemo/URDF2Bullet.h"
  22. #include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
  23. #include "../CommonInterfaces/CommonMultiBodyBase.h"
  24. #include "btBulletDynamicsCommon.h"
  25. #include "LinearMath/btVector3.h"
  26. #include "LinearMath/btAlignedObjectArray.h"
  27. #include "../CommonInterfaces/CommonRigidBodyBase.h"
  28. #include "BulletInverseDynamics/IDConfig.hpp"
  29. #include "../Extras/InverseDynamics/btMultiBodyTreeCreator.hpp"
  30. #include "../RenderingExamples/TimeSeriesCanvas.h"
  31. #include <vector>
  32. // the UI interface makes it easier to use static variables & free functions
  33. // as parameters and callbacks
  34. static btScalar kp =10*10;
  35. static btScalar kd = 2*10;
  36. static bool useInverseModel = true;
  37. static std::vector<btScalar> qd;
  38. static std::vector<std::string> qd_name;
  39. static std::vector<std::string> q_name;
  40. static btVector4 sJointCurveColors[8] =
  41. {
  42. btVector4(1,0.3,0.3,1),
  43. btVector4(0.3,1,0.3,1),
  44. btVector4(0.3,0.3,1,1),
  45. btVector4(0.3,1,1,1),
  46. btVector4(1,0.3,1,1),
  47. btVector4(1,1,0.3,1),
  48. btVector4(1,0.7,0.7,1),
  49. btVector4(0.7,1,1,1),
  50. };
  51. void toggleUseInverseModel(int buttonId, bool buttonState, void* userPointer){
  52. useInverseModel=!useInverseModel;
  53. // todo(thomas) is there a way to get a toggle button with changing text?
  54. b3Printf("switched inverse model %s", useInverseModel?"on":"off");
  55. }
  56. class InverseDynamicsExample : public CommonMultiBodyBase
  57. {
  58. btInverseDynamicsExampleOptions m_option;
  59. btMultiBody* m_multiBody;
  60. btInverseDynamics::MultiBodyTree *m_inverseModel;
  61. TimeSeriesCanvas* m_timeSeriesCanvas;
  62. public:
  63. InverseDynamicsExample(struct GUIHelperInterface* helper, btInverseDynamicsExampleOptions option);
  64. virtual ~InverseDynamicsExample();
  65. virtual void initPhysics();
  66. virtual void stepSimulation(float deltaTime);
  67. void setFileName(const char* urdfFileName);
  68. virtual void resetCamera()
  69. {
  70. float dist = 1.5;
  71. float pitch = -80;
  72. float yaw = 10;
  73. float targetPos[3]={0,0,0};
  74. m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
  75. }
  76. };
  77. InverseDynamicsExample::InverseDynamicsExample(struct GUIHelperInterface* helper, btInverseDynamicsExampleOptions option)
  78. :CommonMultiBodyBase(helper),
  79. m_option(option),
  80. m_multiBody(0),
  81. m_inverseModel(0),
  82. m_timeSeriesCanvas(0)
  83. {
  84. }
  85. InverseDynamicsExample::~InverseDynamicsExample()
  86. {
  87. delete m_inverseModel;
  88. delete m_timeSeriesCanvas;
  89. }
  90. //todo(erwincoumans) Quick hack, reference to InvertedPendulumPDControl implementation. Will create a separate header/source file for this.
  91. btMultiBody* createInvertedPendulumMultiBody(btMultiBodyDynamicsWorld* world, GUIHelperInterface* guiHelper, const btTransform& baseWorldTrans, bool fixedBase);
  92. void InverseDynamicsExample::initPhysics()
  93. {
  94. //roboticists like Z up
  95. int upAxis = 2;
  96. m_guiHelper->setUpAxis(upAxis);
  97. createEmptyDynamicsWorld();
  98. btVector3 gravity(0,0,0);
  99. // gravity[upAxis]=-9.8;
  100. m_dynamicsWorld->setGravity(gravity);
  101. m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
  102. {
  103. SliderParams slider("Kp",&kp);
  104. slider.m_minVal=0;
  105. slider.m_maxVal=2000;
  106. if (m_guiHelper->getParameterInterface())
  107. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  108. }
  109. {
  110. SliderParams slider("Kd",&kd);
  111. slider.m_minVal=0;
  112. slider.m_maxVal=50;
  113. if (m_guiHelper->getParameterInterface())
  114. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  115. }
  116. if (m_option == BT_ID_PROGRAMMATICALLY)
  117. {
  118. ButtonParams button("toggle inverse model",0,true);
  119. button.m_callback = toggleUseInverseModel;
  120. m_guiHelper->getParameterInterface()->registerButtonParameter(button);
  121. }
  122. switch (m_option)
  123. {
  124. case BT_ID_LOAD_URDF:
  125. {
  126. BulletURDFImporter u2b(m_guiHelper,0);
  127. bool loadOk = u2b.loadURDF("kuka_iiwa/model.urdf");// lwr / kuka.urdf");
  128. if (loadOk)
  129. {
  130. int rootLinkIndex = u2b.getRootLinkIndex();
  131. b3Printf("urdf root link index = %d\n",rootLinkIndex);
  132. MyMultiBodyCreator creation(m_guiHelper);
  133. btTransform identityTrans;
  134. identityTrans.setIdentity();
  135. ConvertURDF2Bullet(u2b,creation, identityTrans,m_dynamicsWorld,true,u2b.getPathPrefix());
  136. for (int i = 0; i < u2b.getNumAllocatedCollisionShapes(); i++)
  137. {
  138. m_collisionShapes.push_back(u2b.getAllocatedCollisionShape(i));
  139. }
  140. m_multiBody = creation.getBulletMultiBody();
  141. if (m_multiBody)
  142. {
  143. //kuka without joint control/constraints will gain energy explode soon due to timestep/integrator
  144. //temporarily set some extreme damping factors until we have some joint control or constraints
  145. m_multiBody->setAngularDamping(0*0.99);
  146. m_multiBody->setLinearDamping(0*0.99);
  147. b3Printf("Root link name = %s",u2b.getLinkName(u2b.getRootLinkIndex()).c_str());
  148. }
  149. }
  150. break;
  151. }
  152. case BT_ID_PROGRAMMATICALLY:
  153. {
  154. btTransform baseWorldTrans;
  155. baseWorldTrans.setIdentity();
  156. m_multiBody = createInvertedPendulumMultiBody(m_dynamicsWorld, m_guiHelper, baseWorldTrans, false);
  157. break;
  158. }
  159. default:
  160. {
  161. b3Error("Unknown option in InverseDynamicsExample::initPhysics");
  162. b3Assert(0);
  163. }
  164. };
  165. if(m_multiBody) {
  166. {
  167. if (m_guiHelper->getAppInterface() && m_guiHelper->getParameterInterface())
  168. {
  169. m_timeSeriesCanvas = new TimeSeriesCanvas(m_guiHelper->getAppInterface()->m_2dCanvasInterface,512,230, "Joint Space Trajectory");
  170. m_timeSeriesCanvas ->setupTimeSeries(3,100, 0);
  171. }
  172. }
  173. // construct inverse model
  174. btInverseDynamics::btMultiBodyTreeCreator id_creator;
  175. if (-1 == id_creator.createFromBtMultiBody(m_multiBody, false)) {
  176. b3Error("error creating tree\n");
  177. } else {
  178. m_inverseModel = btInverseDynamics::CreateMultiBodyTree(id_creator);
  179. }
  180. // add joint target controls
  181. qd.resize(m_multiBody->getNumDofs());
  182. qd_name.resize(m_multiBody->getNumDofs());
  183. q_name.resize(m_multiBody->getNumDofs());
  184. if (m_timeSeriesCanvas && m_guiHelper->getParameterInterface())
  185. {
  186. for(std::size_t dof=0;dof<qd.size();dof++)
  187. {
  188. qd[dof] = 0;
  189. char tmp[25];
  190. sprintf(tmp,"q_desired[%u]",dof);
  191. qd_name[dof] = tmp;
  192. SliderParams slider(qd_name[dof].c_str(),&qd[dof]);
  193. slider.m_minVal=-3.14;
  194. slider.m_maxVal=3.14;
  195. sprintf(tmp,"q[%u]",dof);
  196. q_name[dof] = tmp;
  197. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  198. btVector4 color = sJointCurveColors[dof&7];
  199. m_timeSeriesCanvas->addDataSource(q_name[dof].c_str(), color[0]*255,color[1]*255,color[2]*255);
  200. }
  201. }
  202. }
  203. m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
  204. }
  205. void InverseDynamicsExample::stepSimulation(float deltaTime)
  206. {
  207. if(m_multiBody) {
  208. const int num_dofs=m_multiBody->getNumDofs();
  209. btInverseDynamics::vecx nu(num_dofs), qdot(num_dofs), q(num_dofs),joint_force(num_dofs);
  210. btInverseDynamics::vecx pd_control(num_dofs);
  211. // compute joint forces from one of two control laws:
  212. // 1) "computed torque" control, which gives perfect, decoupled,
  213. // linear second order error dynamics per dof in case of a
  214. // perfect model and (and negligible time discretization effects)
  215. // 2) decoupled PD control per joint, without a model
  216. for(int dof=0;dof<num_dofs;dof++) {
  217. q(dof) = m_multiBody->getJointPos(dof);
  218. qdot(dof)= m_multiBody->getJointVel(dof);
  219. const btScalar qd_dot=0;
  220. const btScalar qd_ddot=0;
  221. if (m_timeSeriesCanvas)
  222. m_timeSeriesCanvas->insertDataAtCurrentTime(q[dof],dof,true);
  223. // pd_control is either desired joint torque for pd control,
  224. // or the feedback contribution to nu
  225. pd_control(dof) = kd*(qd_dot-qdot(dof)) + kp*(qd[dof]-q(dof));
  226. // nu is the desired joint acceleration for computed torque control
  227. nu(dof) = qd_ddot + pd_control(dof);
  228. }
  229. if(useInverseModel)
  230. {
  231. // calculate joint forces corresponding to desired accelerations nu
  232. if (m_multiBody->hasFixedBase())
  233. {
  234. if(-1 != m_inverseModel->calculateInverseDynamics(q,qdot,nu,&joint_force))
  235. {
  236. //joint_force(dof) += damping*dot_q(dof);
  237. // use inverse model: apply joint force corresponding to
  238. // desired acceleration nu
  239. for(int dof=0;dof<num_dofs;dof++)
  240. {
  241. m_multiBody->addJointTorque(dof,joint_force(dof));
  242. }
  243. }
  244. } else
  245. {
  246. //the inverse dynamics model represents the 6 DOFs of the base, unlike btMultiBody.
  247. //append some dummy values to represent the 6 DOFs of the base
  248. btInverseDynamics::vecx nu6(num_dofs+6), qdot6(num_dofs+6), q6(num_dofs+6),joint_force6(num_dofs+6);
  249. for (int i=0;i<num_dofs;i++)
  250. {
  251. nu6[6+i] = nu[i];
  252. qdot6[6+i] = qdot[i];
  253. q6[6+i] = q[i];
  254. joint_force6[6+i] = joint_force[i];
  255. }
  256. if(-1 != m_inverseModel->calculateInverseDynamics(q6,qdot6,nu6,&joint_force6))
  257. {
  258. //joint_force(dof) += damping*dot_q(dof);
  259. // use inverse model: apply joint force corresponding to
  260. // desired acceleration nu
  261. for(int dof=0;dof<num_dofs;dof++)
  262. {
  263. m_multiBody->addJointTorque(dof,joint_force6(dof+6));
  264. }
  265. }
  266. }
  267. } else
  268. {
  269. for(int dof=0;dof<num_dofs;dof++)
  270. {
  271. // no model: just apply PD control law
  272. m_multiBody->addJointTorque(dof,pd_control(dof));
  273. }
  274. }
  275. }
  276. if (m_timeSeriesCanvas)
  277. m_timeSeriesCanvas->nextTick();
  278. //todo: joint damping for btMultiBody, tune parameters
  279. // step the simulation
  280. if (m_dynamicsWorld)
  281. {
  282. // todo(thomas) check that this is correct:
  283. // want to advance by 10ms, with 1ms timesteps
  284. m_dynamicsWorld->stepSimulation(1e-3,0);//,1e-3);
  285. btAlignedObjectArray<btQuaternion> scratch_q;
  286. btAlignedObjectArray<btVector3> scratch_m;
  287. m_multiBody->forwardKinematics(scratch_q, scratch_m);
  288. for (int i = 0; i < m_multiBody->getNumLinks(); i++)
  289. {
  290. //btVector3 pos = m_multiBody->getLink(i).m_cachedWorldTransform.getOrigin();
  291. btTransform tr = m_multiBody->getLink(i).m_cachedWorldTransform;
  292. btVector3 pos = tr.getOrigin() - quatRotate(tr.getRotation(), m_multiBody->getLink(i).m_dVector);
  293. btVector3 localAxis = m_multiBody->getLink(i).m_axes[0].m_topVec;
  294. //printf("link %d: %f,%f,%f, local axis:%f,%f,%f\n", i, pos.x(), pos.y(), pos.z(), localAxis.x(), localAxis.y(), localAxis.z());
  295. }
  296. }
  297. }
  298. CommonExampleInterface* InverseDynamicsExampleCreateFunc(CommonExampleOptions& options)
  299. {
  300. return new InverseDynamicsExample(options.m_guiHelper, btInverseDynamicsExampleOptions(options.m_option));
  301. }
  302. B3_STANDALONE_EXAMPLE(InverseDynamicsExampleCreateFunc)