test_invdyn_kinematics.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373
  1. // Test of kinematic consistency: check if finite differences of velocities, accelerations
  2. // match positions
  3. #include <cmath>
  4. #include <cstdio>
  5. #include <cstdlib>
  6. #include <iostream>
  7. #include <gtest/gtest.h>
  8. #include "../Extras/InverseDynamics/CoilCreator.hpp"
  9. #include "../Extras/InverseDynamics/DillCreator.hpp"
  10. #include "../Extras/InverseDynamics/SimpleTreeCreator.hpp"
  11. #include "BulletInverseDynamics/MultiBodyTree.hpp"
  12. using namespace btInverseDynamics;
  13. const int kLevel = 5;
  14. const int kNumBodies = BT_ID_POW(2, kLevel);
  15. // template function for calculating the norm
  16. template <typename T>
  17. idScalar calculateNorm(T&);
  18. // only implemented for vec3
  19. template <>
  20. idScalar calculateNorm(vec3& v) {
  21. return std::sqrt(BT_ID_POW(v(0), 2) + BT_ID_POW(v(1), 2) + BT_ID_POW(v(2), 2));
  22. }
  23. // template function to convert a DiffType (finite differences)
  24. // to a ValueType. This is for angular velocity calculations
  25. // via finite differences.
  26. template <typename ValueType, typename DiffType>
  27. DiffType toDiffType(ValueType& fd, ValueType& val);
  28. // vector case: just return finite difference approximation
  29. template <>
  30. vec3 toDiffType(vec3& fd, vec3& val) {
  31. return fd;
  32. }
  33. // orientation case: calculate spin tensor and extract angular velocity
  34. template <>
  35. vec3 toDiffType(mat33& fd, mat33& val) {
  36. // spin tensor
  37. mat33 omega_tilde = fd * val.transpose();
  38. // extract vector from spin tensor
  39. vec3 omega;
  40. omega(0) = 0.5 * (omega_tilde(2, 1) - omega_tilde(1, 2));
  41. omega(1) = 0.5 * (omega_tilde(0, 2) - omega_tilde(2, 0));
  42. omega(2) = 0.5 * (omega_tilde(1, 0) - omega_tilde(0, 1));
  43. return omega;
  44. }
  45. /// Class for calculating finite difference approximation
  46. /// of time derivatives and comparing it to an analytical solution
  47. /// DiffType and ValueType can be different, to allow comparison
  48. /// of angular velocity vectors and orientations given as transform matrices.
  49. template <typename ValueType, typename DiffType>
  50. class DiffFD {
  51. public:
  52. DiffFD() : m_dt(0.0), m_num_updates(0), m_max_error(0.0), m_max_value(0.0), m_valid_fd(false) {}
  53. void init(std::string name, idScalar dt) {
  54. m_name = name;
  55. m_dt = dt;
  56. m_num_updates = 0;
  57. m_max_error = 0.0;
  58. m_max_value = 0.0;
  59. m_valid_fd = false;
  60. }
  61. void update(const ValueType& val, const DiffType& true_diff) {
  62. m_val = val;
  63. if (m_num_updates > 2) {
  64. // 2nd order finite difference approximation for d(value)/dt
  65. ValueType diff_value_fd = (val - m_older_val) / (2.0 * m_dt);
  66. // convert to analytical diff type. This is for angular velocities
  67. m_diff_fd = toDiffType<ValueType, DiffType>(diff_value_fd, m_old_val);
  68. // now, calculate the error
  69. DiffType error_value_type = m_diff_fd - m_old_true_diff;
  70. idScalar error = calculateNorm<DiffType>(error_value_type);
  71. if (error > m_max_error) {
  72. m_max_error = error;
  73. }
  74. idScalar value = calculateNorm<DiffType>(m_old_true_diff);
  75. if (value > m_max_value) {
  76. m_max_value = value;
  77. }
  78. m_valid_fd = true;
  79. }
  80. m_older_val = m_old_val;
  81. m_old_val = m_val;
  82. m_old_true_diff = true_diff;
  83. m_num_updates++;
  84. m_time += m_dt;
  85. }
  86. void printMaxError() {
  87. printf("max_error: %e dt= %e max_value= %e fraction= %e\n", m_max_error, m_dt, m_max_value,
  88. m_max_value > 0.0 ? m_max_error / m_max_value : 0.0);
  89. }
  90. void printCurrent() {
  91. if (m_valid_fd) {
  92. // note: m_old_true_diff already equals m_true_diff here, so values are not aligned.
  93. // (but error calculation takes this into account)
  94. printf("%s time: %e fd: %e %e %e true: %e %e %e\n", m_name.c_str(), m_time,
  95. m_diff_fd(0), m_diff_fd(1), m_diff_fd(2), m_old_true_diff(0), m_old_true_diff(1),
  96. m_old_true_diff(2));
  97. }
  98. }
  99. idScalar getMaxError() const { return m_max_error; }
  100. idScalar getMaxValue() const { return m_max_value; }
  101. private:
  102. idScalar m_dt;
  103. ValueType m_val;
  104. ValueType m_old_val;
  105. ValueType m_older_val;
  106. DiffType m_old_true_diff;
  107. DiffType m_diff_fd;
  108. int m_num_updates;
  109. idScalar m_max_error;
  110. idScalar m_max_value;
  111. idScalar m_time;
  112. std::string m_name;
  113. bool m_valid_fd;
  114. };
  115. template <typename ValueType, typename DiffType>
  116. class VecDiffFD {
  117. public:
  118. VecDiffFD(std::string name, int dim, idScalar dt) : m_name(name), m_fd(dim), m_dt(dt) {
  119. for (int i = 0; i < m_fd.size(); i++) {
  120. char buf[256];
  121. BT_ID_SNPRINTF(buf, 256, "%s-%.2d", name.c_str(), i);
  122. m_fd[i].init(buf, dt);
  123. }
  124. }
  125. void update(int i, ValueType& val, DiffType& true_diff) { m_fd[i].update(val, true_diff); }
  126. idScalar getMaxError() const {
  127. idScalar max_error = 0;
  128. for (int i = 0; i < m_fd.size(); i++) {
  129. const idScalar error = m_fd[i].getMaxError();
  130. if (error > max_error) {
  131. max_error = error;
  132. }
  133. }
  134. return max_error;
  135. }
  136. idScalar getMaxValue() const {
  137. idScalar max_value = 0;
  138. for (int i = 0; i < m_fd.size(); i++) {
  139. const idScalar value = m_fd[i].getMaxValue();
  140. if (value > max_value) {
  141. max_value= value;
  142. }
  143. }
  144. return max_value;
  145. }
  146. void printMaxError() {
  147. printf("%s: total dt= %e max_error= %e\n", m_name.c_str(), m_dt, getMaxError());
  148. }
  149. void printCurrent() {
  150. for (int i = 0; i < m_fd.size(); i++) {
  151. m_fd[i].printCurrent();
  152. }
  153. }
  154. private:
  155. std::string m_name;
  156. std::vector<DiffFD<ValueType, DiffType> > m_fd;
  157. const idScalar m_dt;
  158. idScalar m_max_error;
  159. };
  160. // calculate maximum difference between finite difference and analytical differentiation
  161. int calculateDifferentiationError(const MultiBodyTreeCreator& creator, idScalar deltaT,
  162. idScalar endTime, idScalar* max_linear_velocity_error,
  163. idScalar* max_angular_velocity_error,
  164. idScalar* max_linear_acceleration_error,
  165. idScalar* max_angular_acceleration_error) {
  166. // setup system
  167. MultiBodyTree* tree = CreateMultiBodyTree(creator);
  168. if (0x0 == tree) {
  169. return -1;
  170. }
  171. // set gravity to zero, so nothing is added to accelerations in forward kinematics
  172. vec3 gravity_zero;
  173. gravity_zero(0) = 0;
  174. gravity_zero(1) = 0;
  175. gravity_zero(2) = 0;
  176. tree->setGravityInWorldFrame(gravity_zero);
  177. //
  178. const idScalar kAmplitude = 1.0;
  179. const idScalar kFrequency = 1.0;
  180. vecx q(tree->numDoFs());
  181. vecx dot_q(tree->numDoFs());
  182. vecx ddot_q(tree->numDoFs());
  183. vecx joint_forces(tree->numDoFs());
  184. VecDiffFD<vec3, vec3> fd_vel("linear-velocity", tree->numBodies(), deltaT);
  185. VecDiffFD<vec3, vec3> fd_acc("linear-acceleration", tree->numBodies(), deltaT);
  186. VecDiffFD<mat33, vec3> fd_omg("angular-velocity", tree->numBodies(), deltaT);
  187. VecDiffFD<vec3, vec3> fd_omgd("angular-acceleration", tree->numBodies(), deltaT);
  188. for (idScalar t = 0.0; t < endTime; t += deltaT) {
  189. for (int body = 0; body < tree->numBodies(); body++) {
  190. q(body) = kAmplitude * sin(t * 2.0 * BT_ID_PI * kFrequency);
  191. dot_q(body) = kAmplitude * 2.0 * BT_ID_PI * kFrequency * cos(t * 2.0 * BT_ID_PI * kFrequency);
  192. ddot_q(body) =
  193. -kAmplitude * pow(2.0 * BT_ID_PI * kFrequency, 2) * sin(t * 2.0 * BT_ID_PI * kFrequency);
  194. }
  195. if (-1 == tree->calculateInverseDynamics(q, dot_q, ddot_q, &joint_forces)) {
  196. delete tree;
  197. return -1;
  198. }
  199. // position/velocity
  200. for (int body = 0; body < tree->numBodies(); body++) {
  201. vec3 pos;
  202. vec3 vel;
  203. mat33 world_T_body;
  204. vec3 omega;
  205. vec3 dot_omega;
  206. vec3 acc;
  207. tree->getBodyOrigin(body, &pos);
  208. tree->getBodyTransform(body, &world_T_body);
  209. tree->getBodyLinearVelocity(body, &vel);
  210. tree->getBodyAngularVelocity(body, &omega);
  211. tree->getBodyLinearAcceleration(body, &acc);
  212. tree->getBodyAngularAcceleration(body, &dot_omega);
  213. fd_vel.update(body, pos, vel);
  214. fd_omg.update(body, world_T_body, omega);
  215. fd_acc.update(body, vel, acc);
  216. fd_omgd.update(body, omega, dot_omega);
  217. // fd_vel.printCurrent();
  218. //fd_acc.printCurrent();
  219. //fd_omg.printCurrent();
  220. //fd_omgd.printCurrent();
  221. }
  222. }
  223. *max_linear_velocity_error = fd_vel.getMaxError()/fd_vel.getMaxValue();
  224. *max_angular_velocity_error = fd_omg.getMaxError()/fd_omg.getMaxValue();
  225. *max_linear_acceleration_error = fd_acc.getMaxError()/fd_acc.getMaxValue();
  226. *max_angular_acceleration_error = fd_omgd.getMaxError()/fd_omgd.getMaxValue();
  227. delete tree;
  228. return 0;
  229. }
  230. // first test: absolute difference between numerical and numerial
  231. // differentiation should be small
  232. TEST(InvDynKinematicsDifferentiation, errorAbsolute) {
  233. //CAVEAT:these values are hand-tuned to work for the specific trajectory defined above.
  234. #ifdef BT_ID_USE_DOUBLE_PRECISION
  235. const idScalar kDeltaT = 1e-7;
  236. const idScalar kAcceptableError = 1e-4;
  237. #else
  238. const idScalar kDeltaT = 1e-4;
  239. const idScalar kAcceptableError = 5e-3;
  240. #endif
  241. const idScalar kDuration = 0.01;
  242. CoilCreator coil_creator(kNumBodies);
  243. DillCreator dill_creator(kLevel);
  244. SimpleTreeCreator simple_creator(kNumBodies);
  245. idScalar max_linear_velocity_error;
  246. idScalar max_angular_velocity_error;
  247. idScalar max_linear_acceleration_error;
  248. idScalar max_angular_acceleration_error;
  249. // test serial chain
  250. calculateDifferentiationError(coil_creator, kDeltaT, kDuration, &max_linear_velocity_error,
  251. &max_angular_velocity_error, &max_linear_acceleration_error,
  252. &max_angular_acceleration_error);
  253. EXPECT_LT(max_linear_velocity_error, kAcceptableError);
  254. EXPECT_LT(max_angular_velocity_error, kAcceptableError);
  255. EXPECT_LT(max_linear_acceleration_error, kAcceptableError);
  256. EXPECT_LT(max_angular_acceleration_error, kAcceptableError);
  257. // test branched tree
  258. calculateDifferentiationError(dill_creator, kDeltaT, kDuration, &max_linear_velocity_error,
  259. &max_angular_velocity_error, &max_linear_acceleration_error,
  260. &max_angular_acceleration_error);
  261. EXPECT_LT(max_linear_velocity_error, kAcceptableError);
  262. EXPECT_LT(max_angular_velocity_error, kAcceptableError);
  263. EXPECT_LT(max_linear_acceleration_error, kAcceptableError);
  264. EXPECT_LT(max_angular_acceleration_error, kAcceptableError);
  265. // test system with different joint types
  266. calculateDifferentiationError(simple_creator, kDeltaT, kDuration, &max_linear_velocity_error,
  267. &max_angular_velocity_error, &max_linear_acceleration_error,
  268. &max_angular_acceleration_error);
  269. EXPECT_LT(max_linear_velocity_error, kAcceptableError);
  270. EXPECT_LT(max_angular_velocity_error, kAcceptableError);
  271. EXPECT_LT(max_linear_acceleration_error, kAcceptableError);
  272. EXPECT_LT(max_angular_acceleration_error, kAcceptableError);
  273. }
  274. // second test: check if the change in the differentiation error
  275. // is consitent with the second order approximation, ie, error ~ O(dt^2)
  276. TEST(InvDynKinematicsDifferentiation, errorOrder) {
  277. const idScalar kDeltaTs[2] = {1e-4, 1e-5};
  278. const idScalar kDuration = 1e-2;
  279. CoilCreator coil_creator(kNumBodies);
  280. // DillCreator dill_creator(kLevel);
  281. // SimpleTreeCreator simple_creator(kNumBodies);
  282. idScalar max_linear_velocity_error[2];
  283. idScalar max_angular_velocity_error[2];
  284. idScalar max_linear_acceleration_error[2];
  285. idScalar max_angular_acceleration_error[2];
  286. // test serial chain
  287. calculateDifferentiationError(coil_creator, kDeltaTs[0], kDuration,
  288. &max_linear_velocity_error[0], &max_angular_velocity_error[0],
  289. &max_linear_acceleration_error[0],
  290. &max_angular_acceleration_error[0]);
  291. calculateDifferentiationError(coil_creator, kDeltaTs[1], kDuration,
  292. &max_linear_velocity_error[1], &max_angular_velocity_error[1],
  293. &max_linear_acceleration_error[1],
  294. &max_angular_acceleration_error[1]);
  295. const idScalar expected_linear_velocity_error_1 =
  296. max_linear_velocity_error[0] * pow(kDeltaTs[1] / kDeltaTs[0], 2);
  297. const idScalar expected_angular_velocity_error_1 =
  298. max_angular_velocity_error[0] * pow(kDeltaTs[1] / kDeltaTs[0], 2);
  299. const idScalar expected_linear_acceleration_error_1 =
  300. max_linear_acceleration_error[0] * pow(kDeltaTs[1] / kDeltaTs[0], 2);
  301. const idScalar expected_angular_acceleration_error_1 =
  302. max_angular_acceleration_error[0] * pow(kDeltaTs[1] / kDeltaTs[0], 2);
  303. /* printf("linear vel error: %e %e %e\n", max_linear_velocity_error[1],
  304. expected_linear_velocity_error_1,
  305. max_linear_velocity_error[1] - expected_linear_velocity_error_1);
  306. printf("angular vel error: %e %e %e\n", max_angular_velocity_error[1],
  307. expected_angular_velocity_error_1,
  308. max_angular_velocity_error[1] - expected_angular_velocity_error_1);
  309. printf("linear acc error: %e %e %e\n", max_linear_acceleration_error[1],
  310. expected_linear_acceleration_error_1,
  311. max_linear_acceleration_error[1] - expected_linear_acceleration_error_1);
  312. printf("angular acc error: %e %e %e\n", max_angular_acceleration_error[1],
  313. expected_angular_acceleration_error_1,
  314. max_angular_acceleration_error[1] - expected_angular_acceleration_error_1);
  315. */
  316. }
  317. int main(int argc, char** argv) {
  318. ::testing::InitGoogleTest(&argc, argv);
  319. return RUN_ALL_TESTS();
  320. return EXIT_SUCCESS;
  321. }