invdyn_bullet_comparison.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361
  1. #include "invdyn_bullet_comparison.hpp"
  2. #include <cmath>
  3. #include "BulletInverseDynamics/IDConfig.hpp"
  4. #include "BulletInverseDynamics/MultiBodyTree.hpp"
  5. #include "btBulletDynamicsCommon.h"
  6. #include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
  7. #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
  8. #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
  9. #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
  10. namespace btInverseDynamics
  11. {
  12. int compareInverseAndForwardDynamics(vecx &q, vecx &u, vecx &dot_u, btVector3 &gravity, bool verbose,
  13. btMultiBody *btmb, MultiBodyTree *id_tree, double *pos_error,
  14. double *acc_error)
  15. {
  16. // call function and return -1 if it does, printing an bt_id_error_message
  17. #define RETURN_ON_FAILURE(x) \
  18. do \
  19. { \
  20. if (-1 == x) \
  21. { \
  22. bt_id_error_message("calling " #x "\n"); \
  23. return -1; \
  24. } \
  25. } while (0)
  26. if (verbose)
  27. {
  28. printf("\n ===================================== \n");
  29. }
  30. vecx joint_forces(q.size());
  31. // set positions and velocities for btMultiBody
  32. // base link
  33. mat33 world_T_base;
  34. vec3 world_pos_base;
  35. btTransform base_transform;
  36. vec3 base_velocity;
  37. vec3 base_angular_velocity;
  38. RETURN_ON_FAILURE(id_tree->setGravityInWorldFrame(gravity));
  39. RETURN_ON_FAILURE(id_tree->getBodyOrigin(0, &world_pos_base));
  40. RETURN_ON_FAILURE(id_tree->getBodyTransform(0, &world_T_base));
  41. RETURN_ON_FAILURE(id_tree->getBodyAngularVelocity(0, &base_angular_velocity));
  42. RETURN_ON_FAILURE(id_tree->getBodyLinearVelocityCoM(0, &base_velocity));
  43. base_transform.setBasis(world_T_base);
  44. base_transform.setOrigin(world_pos_base);
  45. btmb->setBaseWorldTransform(base_transform);
  46. btmb->setBaseOmega(base_angular_velocity);
  47. btmb->setBaseVel(base_velocity);
  48. btmb->setLinearDamping(0);
  49. btmb->setAngularDamping(0);
  50. // remaining links
  51. int q_index;
  52. if (btmb->hasFixedBase())
  53. {
  54. q_index = 0;
  55. }
  56. else
  57. {
  58. q_index = 6;
  59. }
  60. if (verbose)
  61. {
  62. printf("bt:num_links= %d, num_dofs= %d\n", btmb->getNumLinks(), btmb->getNumDofs());
  63. }
  64. for (int l = 0; l < btmb->getNumLinks(); l++)
  65. {
  66. const btMultibodyLink &link = btmb->getLink(l);
  67. if (verbose)
  68. {
  69. printf("link %d, pos_var_count= %d, dof_count= %d\n", l, link.m_posVarCount,
  70. link.m_dofCount);
  71. }
  72. if (link.m_posVarCount == 1)
  73. {
  74. btmb->setJointPosMultiDof(l, &q(q_index));
  75. btmb->setJointVelMultiDof(l, &u(q_index));
  76. if (verbose)
  77. {
  78. printf("set q[%d]= %f, u[%d]= %f\n", q_index, q(q_index), q_index, u(q_index));
  79. }
  80. q_index++;
  81. }
  82. }
  83. // sanity check
  84. if (q_index != q.size())
  85. {
  86. bt_id_error_message("error in number of dofs for btMultibody and MultiBodyTree\n");
  87. return -1;
  88. }
  89. // run inverse dynamics to determine joint_forces for given q, u, dot_u
  90. if (-1 == id_tree->calculateInverseDynamics(q, u, dot_u, &joint_forces))
  91. {
  92. bt_id_error_message("calculating inverse dynamics\n");
  93. return -1;
  94. }
  95. // set up bullet forward dynamics model
  96. btScalar dt = 0;
  97. btAlignedObjectArray<btScalar> scratch_r;
  98. btAlignedObjectArray<btVector3> scratch_v;
  99. btAlignedObjectArray<btMatrix3x3> scratch_m;
  100. // this triggers switch between using either appliedConstraintForce or appliedForce
  101. bool isConstraintPass = false;
  102. // apply gravity forces for btMultiBody model. Must be done manually.
  103. btmb->addBaseForce(btmb->getBaseMass() * gravity);
  104. for (int link = 0; link < btmb->getNumLinks(); link++)
  105. {
  106. btmb->addLinkForce(link, gravity * btmb->getLinkMass(link));
  107. if (verbose)
  108. {
  109. printf("link %d, applying gravity %f %f %f\n", link,
  110. gravity[0] * btmb->getLinkMass(link), gravity[1] * btmb->getLinkMass(link),
  111. gravity[2] * btmb->getLinkMass(link));
  112. }
  113. }
  114. // apply generalized forces
  115. if (btmb->hasFixedBase())
  116. {
  117. q_index = 0;
  118. }
  119. else
  120. {
  121. vec3 base_force;
  122. base_force(0) = joint_forces(3);
  123. base_force(1) = joint_forces(4);
  124. base_force(2) = joint_forces(5);
  125. vec3 base_moment;
  126. base_moment(0) = joint_forces(0);
  127. base_moment(1) = joint_forces(1);
  128. base_moment(2) = joint_forces(2);
  129. btmb->addBaseForce(world_T_base * base_force);
  130. btmb->addBaseTorque(world_T_base * base_moment);
  131. if (verbose)
  132. {
  133. printf("base force from id: %f %f %f\n", joint_forces(3), joint_forces(4),
  134. joint_forces(5));
  135. printf("base moment from id: %f %f %f\n", joint_forces(0), joint_forces(1),
  136. joint_forces(2));
  137. }
  138. q_index = 6;
  139. }
  140. for (int l = 0; l < btmb->getNumLinks(); l++)
  141. {
  142. const btMultibodyLink &link = btmb->getLink(l);
  143. if (link.m_posVarCount == 1)
  144. {
  145. if (verbose)
  146. {
  147. printf("id:joint_force[%d]= %f, applied to link %d\n", q_index,
  148. joint_forces(q_index), l);
  149. }
  150. btmb->addJointTorque(l, joint_forces(q_index));
  151. q_index++;
  152. }
  153. }
  154. // sanity check
  155. if (q_index != q.size())
  156. {
  157. bt_id_error_message("error in number of dofs for btMultibody and MultiBodyTree\n");
  158. return -1;
  159. }
  160. // run forward kinematics & forward dynamics
  161. btAlignedObjectArray<btQuaternion> world_to_local;
  162. btAlignedObjectArray<btVector3> local_origin;
  163. btmb->forwardKinematics(world_to_local, local_origin);
  164. btmb->computeAccelerationsArticulatedBodyAlgorithmMultiDof(dt, scratch_r, scratch_v, scratch_m, isConstraintPass, false, false);
  165. // read generalized accelerations back from btMultiBody
  166. // the mapping from scratch variables to accelerations is taken from the implementation
  167. // of stepVelocitiesMultiDof
  168. btScalar *base_accel = &scratch_r[btmb->getNumDofs()];
  169. btScalar *joint_accel = base_accel + 6;
  170. *acc_error = 0;
  171. int dot_u_offset = 0;
  172. if (btmb->hasFixedBase())
  173. {
  174. dot_u_offset = 0;
  175. }
  176. else
  177. {
  178. dot_u_offset = 6;
  179. }
  180. if (true == btmb->hasFixedBase())
  181. {
  182. for (int i = 0; i < btmb->getNumDofs(); i++)
  183. {
  184. if (verbose)
  185. {
  186. printf("bt:ddot_q[%d]= %f, id:ddot_q= %e, diff= %e\n", i, joint_accel[i],
  187. dot_u(i + dot_u_offset), joint_accel[i] - dot_u(i));
  188. }
  189. *acc_error += BT_ID_POW(joint_accel[i] - dot_u(i + dot_u_offset), 2);
  190. }
  191. }
  192. else
  193. {
  194. vec3 base_dot_omega;
  195. vec3 world_dot_omega;
  196. world_dot_omega(0) = base_accel[0];
  197. world_dot_omega(1) = base_accel[1];
  198. world_dot_omega(2) = base_accel[2];
  199. base_dot_omega = world_T_base.transpose() * world_dot_omega;
  200. // com happens to coincide with link origin here. If that changes, we need to calculate
  201. // ddot_com
  202. vec3 base_ddot_com;
  203. vec3 world_ddot_com;
  204. world_ddot_com(0) = base_accel[3];
  205. world_ddot_com(1) = base_accel[4];
  206. world_ddot_com(2) = base_accel[5];
  207. base_ddot_com = world_T_base.transpose() * world_ddot_com;
  208. for (int i = 0; i < 3; i++)
  209. {
  210. if (verbose)
  211. {
  212. printf("bt::base_dot_omega(%d)= %e dot_u[%d]= %e, diff= %e\n", i, base_dot_omega(i),
  213. i, dot_u[i], base_dot_omega(i) - dot_u[i]);
  214. }
  215. *acc_error += BT_ID_POW(base_dot_omega(i) - dot_u(i), 2);
  216. }
  217. for (int i = 0; i < 3; i++)
  218. {
  219. if (verbose)
  220. {
  221. printf("bt::base_ddot_com(%d)= %e dot_u[%d]= %e, diff= %e\n", i, base_ddot_com(i),
  222. i, dot_u[i + 3], base_ddot_com(i) - dot_u[i + 3]);
  223. }
  224. *acc_error += BT_ID_POW(base_ddot_com(i) - dot_u(i + 3), 2);
  225. }
  226. for (int i = 0; i < btmb->getNumDofs(); i++)
  227. {
  228. if (verbose)
  229. {
  230. printf("bt:ddot_q[%d]= %f, id:ddot_q= %e, diff= %e\n", i, joint_accel[i],
  231. dot_u(i + 6), joint_accel[i] - dot_u(i + 6));
  232. }
  233. *acc_error += BT_ID_POW(joint_accel[i] - dot_u(i + 6), 2);
  234. }
  235. }
  236. *acc_error = std::sqrt(*acc_error);
  237. if (verbose)
  238. {
  239. printf("======dynamics-err: %e\n", *acc_error);
  240. }
  241. *pos_error = 0.0;
  242. {
  243. mat33 world_T_body;
  244. if (-1 == id_tree->getBodyTransform(0, &world_T_body))
  245. {
  246. bt_id_error_message("getting transform for body %d\n", 0);
  247. return -1;
  248. }
  249. vec3 world_com;
  250. if (-1 == id_tree->getBodyCoM(0, &world_com))
  251. {
  252. bt_id_error_message("getting com for body %d\n", 0);
  253. return -1;
  254. }
  255. if (verbose)
  256. {
  257. printf("id:com: %f %f %f\n", world_com(0), world_com(1), world_com(2));
  258. printf(
  259. "id:transform: %f %f %f\n"
  260. " %f %f %f\n"
  261. " %f %f %f\n",
  262. world_T_body(0, 0), world_T_body(0, 1), world_T_body(0, 2), world_T_body(1, 0),
  263. world_T_body(1, 1), world_T_body(1, 2), world_T_body(2, 0), world_T_body(2, 1),
  264. world_T_body(2, 2));
  265. }
  266. }
  267. for (int l = 0; l < btmb->getNumLinks(); l++)
  268. {
  269. const btMultibodyLink &bt_link = btmb->getLink(l);
  270. vec3 bt_origin = bt_link.m_cachedWorldTransform.getOrigin();
  271. mat33 bt_basis = bt_link.m_cachedWorldTransform.getBasis();
  272. if (verbose)
  273. {
  274. printf("------------- link %d\n", l + 1);
  275. printf("bt:com: %f %f %f\n", bt_origin(0), bt_origin(1), bt_origin(2));
  276. printf(
  277. "bt:transform: %f %f %f\n"
  278. " %f %f %f\n"
  279. " %f %f %f\n",
  280. bt_basis(0, 0), bt_basis(0, 1), bt_basis(0, 2), bt_basis(1, 0), bt_basis(1, 1),
  281. bt_basis(1, 2), bt_basis(2, 0), bt_basis(2, 1), bt_basis(2, 2));
  282. }
  283. mat33 id_world_T_body;
  284. vec3 id_world_com;
  285. if (-1 == id_tree->getBodyTransform(l + 1, &id_world_T_body))
  286. {
  287. bt_id_error_message("getting transform for body %d\n", l);
  288. return -1;
  289. }
  290. if (-1 == id_tree->getBodyCoM(l + 1, &id_world_com))
  291. {
  292. bt_id_error_message("getting com for body %d\n", l);
  293. return -1;
  294. }
  295. if (verbose)
  296. {
  297. printf("id:com: %f %f %f\n", id_world_com(0), id_world_com(1), id_world_com(2));
  298. printf(
  299. "id:transform: %f %f %f\n"
  300. " %f %f %f\n"
  301. " %f %f %f\n",
  302. id_world_T_body(0, 0), id_world_T_body(0, 1), id_world_T_body(0, 2),
  303. id_world_T_body(1, 0), id_world_T_body(1, 1), id_world_T_body(1, 2),
  304. id_world_T_body(2, 0), id_world_T_body(2, 1), id_world_T_body(2, 2));
  305. }
  306. vec3 diff_com = bt_origin - id_world_com;
  307. mat33 diff_basis = bt_basis - id_world_T_body;
  308. if (verbose)
  309. {
  310. printf("diff-com: %e %e %e\n", diff_com(0), diff_com(1), diff_com(2));
  311. printf("diff-transform: %e %e %e %e %e %e %e %e %e\n", diff_basis(0, 0),
  312. diff_basis(0, 1), diff_basis(0, 2), diff_basis(1, 0), diff_basis(1, 1),
  313. diff_basis(1, 2), diff_basis(2, 0), diff_basis(2, 1), diff_basis(2, 2));
  314. }
  315. double total_pos_err =
  316. BT_ID_SQRT(BT_ID_POW(diff_com(0), 2) + BT_ID_POW(diff_com(1), 2) +
  317. BT_ID_POW(diff_com(2), 2) + BT_ID_POW(diff_basis(0, 0), 2) +
  318. BT_ID_POW(diff_basis(0, 1), 2) + BT_ID_POW(diff_basis(0, 2), 2) +
  319. BT_ID_POW(diff_basis(1, 0), 2) + BT_ID_POW(diff_basis(1, 1), 2) +
  320. BT_ID_POW(diff_basis(1, 2), 2) + BT_ID_POW(diff_basis(2, 0), 2) +
  321. BT_ID_POW(diff_basis(2, 1), 2) + BT_ID_POW(diff_basis(2, 2), 2));
  322. if (verbose)
  323. {
  324. printf("======kin-pos-err: %e\n", total_pos_err);
  325. }
  326. if (total_pos_err > *pos_error)
  327. {
  328. *pos_error = total_pos_err;
  329. }
  330. }
  331. return 0;
  332. }
  333. } // namespace btInverseDynamics