TwoJointMain.cpp 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139
  1. /**
  2. * License: Bullet3 license
  3. * Author: Avik De <[email protected]>
  4. */
  5. #include <map>
  6. #include <string>
  7. #include <stdio.h>
  8. #include "../Utils/b3Clock.h"
  9. #include "SharedMemory/PhysicsClientC_API.h"
  10. #include "Bullet3Common/b3Vector3.h"
  11. #include "Bullet3Common/b3Quaternion.h"
  12. #include "SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
  13. extern const int CONTROL_RATE;
  14. const int CONTROL_RATE = 500;
  15. // Bullet globals
  16. b3PhysicsClientHandle kPhysClient = 0;
  17. const b3Scalar FIXED_TIMESTEP = 1.0 / ((b3Scalar)CONTROL_RATE);
  18. // temp vars used a lot
  19. b3SharedMemoryCommandHandle command;
  20. b3SharedMemoryStatusHandle statusHandle;
  21. int statusType, ret;
  22. b3JointInfo jointInfo;
  23. b3JointSensorState state;
  24. // test
  25. int twojoint;
  26. std::map<std::string, int> jointNameToId;
  27. int main(int argc, char* argv[])
  28. {
  29. #ifdef __APPLE__
  30. kPhysClient = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
  31. #else
  32. kPhysClient = b3CreateInProcessPhysicsServerAndConnect(argc, argv);
  33. #endif
  34. if (!kPhysClient)
  35. return -1;
  36. // visualizer
  37. command = b3InitConfigureOpenGLVisualizer(kPhysClient);
  38. b3ConfigureOpenGLVisualizerSetVisualizationFlags(command, COV_ENABLE_GUI, 0);
  39. b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  40. b3ConfigureOpenGLVisualizerSetVisualizationFlags(command, COV_ENABLE_SHADOWS, 0);
  41. b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  42. b3SetTimeOut(kPhysClient, 10);
  43. //syncBodies is only needed when connecting to an existing physics server that has already some bodies
  44. command = b3InitSyncBodyInfoCommand(kPhysClient);
  45. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  46. statusType = b3GetStatusType(statusHandle);
  47. // set fixed time step
  48. command = b3InitPhysicsParamCommand(kPhysClient);
  49. ret = b3PhysicsParamSetTimeStep(command, FIXED_TIMESTEP);
  50. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  51. ret = b3PhysicsParamSetRealTimeSimulation(command, false);
  52. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  53. b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED);
  54. // load test
  55. command = b3LoadUrdfCommandInit(kPhysClient, "TwoJointRobot_wo_fixedJoints.urdf");
  56. int flags = URDF_USE_INERTIA_FROM_FILE;
  57. b3LoadUrdfCommandSetFlags(command, flags);
  58. b3LoadUrdfCommandSetUseFixedBase(command, true);
  59. // q.setEulerZYX(0, 0, 0);
  60. // b3LoadUrdfCommandSetStartOrientation(command, q[0], q[1], q[2], q[3]);
  61. b3LoadUrdfCommandSetUseMultiBody(command, true);
  62. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  63. statusType = b3GetStatusType(statusHandle);
  64. b3Assert(statusType == CMD_URDF_LOADING_COMPLETED);
  65. if (statusType == CMD_URDF_LOADING_COMPLETED)
  66. {
  67. twojoint = b3GetStatusBodyIndex(statusHandle);
  68. }
  69. //disable default linear/angular damping
  70. b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(kPhysClient);
  71. double linearDamping = 0;
  72. double angularDamping = 0;
  73. b3ChangeDynamicsInfoSetLinearDamping(command, twojoint, linearDamping);
  74. b3ChangeDynamicsInfoSetAngularDamping(command, twojoint, angularDamping);
  75. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  76. int numJoints = b3GetNumJoints(kPhysClient, twojoint);
  77. printf("twojoint numjoints = %d\n", numJoints);
  78. // Loop through all joints
  79. for (int i = 0; i < numJoints; ++i)
  80. {
  81. b3GetJointInfo(kPhysClient, twojoint, i, &jointInfo);
  82. if (jointInfo.m_jointName[0])
  83. {
  84. jointNameToId[std::string(jointInfo.m_jointName)] = i;
  85. }
  86. else
  87. {
  88. continue;
  89. }
  90. // Reset before torque control - see #1459
  91. command = b3JointControlCommandInit2(kPhysClient, twojoint, CONTROL_MODE_VELOCITY);
  92. b3JointControlSetDesiredVelocity(command, jointInfo.m_uIndex, 0);
  93. b3JointControlSetMaximumForce(command, jointInfo.m_uIndex, 0);
  94. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  95. }
  96. // loop
  97. unsigned long dtus1 = (unsigned long)1000000.0 * FIXED_TIMESTEP;
  98. double simTimeS = 0;
  99. double q[2], v[2];
  100. while (b3CanSubmitCommand(kPhysClient))
  101. {
  102. simTimeS += 0.000001 * dtus1;
  103. // apply some torque
  104. b3GetJointInfo(kPhysClient, twojoint, jointNameToId["joint_2"], &jointInfo);
  105. command = b3JointControlCommandInit2(kPhysClient, twojoint, CONTROL_MODE_TORQUE);
  106. b3JointControlSetDesiredForceTorque(command, jointInfo.m_uIndex, 0.5 * sin(10 * simTimeS));
  107. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  108. // get joint values
  109. command = b3RequestActualStateCommandInit(kPhysClient, twojoint);
  110. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, command);
  111. b3GetJointState(kPhysClient, statusHandle, jointNameToId["joint_1"], &state);
  112. q[0] = state.m_jointPosition;
  113. v[0] = state.m_jointVelocity;
  114. b3GetJointState(kPhysClient, statusHandle, jointNameToId["joint_2"], &state);
  115. q[1] = state.m_jointPosition;
  116. v[1] = state.m_jointVelocity;
  117. statusHandle = b3SubmitClientCommandAndWaitStatus(kPhysClient, b3InitStepSimulationCommand(kPhysClient));
  118. // debugging output
  119. printf("%.3f\t%.3f\t%.3f\t%.3f\t%.3f\n", simTimeS, q[0], q[1], v[0], v[1]);
  120. b3Clock::usleep(1000. * 1000. * FIXED_TIMESTEP);
  121. }
  122. b3DisconnectSharedMemory(kPhysClient);
  123. return 0;
  124. }