test_invdyn_bullet.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113
  1. /// create a bullet btMultiBody model of a tree structured multibody system,
  2. /// convert that model to a MultiBodyTree model.
  3. /// Then - run inverse dynamics on random input data (q, u, dot_u) to get forces
  4. /// - run forward dynamics on (q,u, forces) to get accelerations
  5. /// - compare input accelerations to inverse dynamics to output from forward dynamics
  6. #include <cmath>
  7. #include <cstdio>
  8. #include <cstdlib>
  9. #include <functional>
  10. #include <string>
  11. #include <btBulletDynamicsCommon.h>
  12. #include <btMultiBodyTreeCreator.hpp>
  13. #include <BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h>
  14. #include <BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h>
  15. #include <BulletDynamics/Featherstone/btMultiBodyPoint2Point.h>
  16. #include <BulletDynamics/Featherstone/btMultiBodyLinkCollider.h>
  17. #include <gtest/gtest.h>
  18. #include "../../examples/CommonInterfaces/CommonGUIHelperInterface.h"
  19. #include "../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.h"
  20. #include "../../examples/Importers/ImportURDFDemo/URDF2Bullet.h"
  21. #include "../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.h"
  22. #include "../../examples/Importers/ImportURDFDemo/URDF2Bullet.h"
  23. #include "../../examples/Utils/b3ResourcePath.h"
  24. #include <invdyn_bullet_comparison.hpp>
  25. #include <btMultiBodyFromURDF.hpp>
  26. #include <MultiBodyTreeCreator.hpp>
  27. #include <MultiBodyTreeDebugGraph.hpp>
  28. #include "Bullet3Common/b3CommandLineArgs.h"
  29. #include "Bullet3Common/b3Random.h"
  30. using namespace btInverseDynamics;
  31. bool FLAGS_verbose=false;
  32. static btVector3 gravity(0, 0, -10);
  33. static const bool kBaseFixed = false;
  34. static const char kUrdfFile[] = "r2d2.urdf";
  35. /// this test loads the a urdf model with fixed, floating, prismatic and rotational joints,
  36. /// converts in to an inverse dynamics model and compares forward to inverse dynamics for
  37. /// random input
  38. TEST(InvDynCompare, bulletUrdfR2D2) {
  39. MyBtMultiBodyFromURDF mb_load(gravity, kBaseFixed);
  40. char relativeFileName[1024];
  41. ASSERT_TRUE(b3ResourcePath::findResourcePath(kUrdfFile, relativeFileName, 1024));
  42. mb_load.setFileName(relativeFileName);
  43. mb_load.init();
  44. btMultiBodyTreeCreator id_creator;
  45. btMultiBody *btmb = mb_load.getBtMultiBody();
  46. ASSERT_EQ(id_creator.createFromBtMultiBody(btmb), 0);
  47. MultiBodyTree *id_tree = CreateMultiBodyTree(id_creator);
  48. ASSERT_EQ(0x0 != id_tree, true);
  49. vecx q(id_tree->numDoFs());
  50. vecx u(id_tree->numDoFs());
  51. vecx dot_u(id_tree->numDoFs());
  52. vecx joint_forces(id_tree->numDoFs());
  53. const int kNLoops = 10;
  54. double max_pos_error = 0;
  55. double max_acc_error = 0;
  56. b3Srand(0);
  57. for (int loop = 0; loop < kNLoops; loop++) {
  58. for (int i = 0; i < q.size(); i++) {
  59. q(i) = b3RandRange(-B3_PI, B3_PI);
  60. u(i) = b3RandRange(-B3_PI, B3_PI);
  61. dot_u(i) = b3RandRange(-B3_PI, B3_PI);
  62. }
  63. double pos_error;
  64. double acc_error;
  65. btmb->clearForcesAndTorques();
  66. id_tree->clearAllUserForcesAndMoments();
  67. // call inverse dynamics once, to get global position & velocity of root body
  68. // (fixed, so q, u, dot_u arbitrary)
  69. EXPECT_EQ(id_tree->calculateInverseDynamics(q, u, dot_u, &joint_forces), 0);
  70. EXPECT_EQ(compareInverseAndForwardDynamics(q, u, dot_u, gravity, FLAGS_verbose, btmb, id_tree,
  71. &pos_error, &acc_error),
  72. 0);
  73. if (pos_error > max_pos_error) {
  74. max_pos_error = pos_error;
  75. }
  76. if (acc_error > max_acc_error) {
  77. max_acc_error = acc_error;
  78. }
  79. }
  80. if (FLAGS_verbose) {
  81. printf("max_pos_error= %e\n", max_pos_error);
  82. printf("max_acc_error= %e\n", max_acc_error);
  83. }
  84. EXPECT_LT(max_pos_error, std::numeric_limits<idScalar>::epsilon()*1e4);
  85. EXPECT_LT(max_acc_error, std::numeric_limits<idScalar>::epsilon()*1e5);
  86. }
  87. int main(int argc, char **argv) {
  88. b3CommandLineArgs myArgs(argc,argv);
  89. FLAGS_verbose = myArgs.CheckCmdLineFlag("verbose");
  90. ::testing::InitGoogleTest(&argc, argv);
  91. return RUN_ALL_TESTS();
  92. }