KukaGraspExample.cpp 9.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  1. #include "KukaGraspExample.h"
  2. #include "../SharedMemory/IKTrajectoryHelper.h"
  3. #include "../CommonInterfaces/CommonGraphicsAppInterface.h"
  4. #include "Bullet3Common/b3Quaternion.h"
  5. #include "Bullet3Common/b3AlignedObjectArray.h"
  6. #include "../CommonInterfaces/CommonRenderInterface.h"
  7. #include "../CommonInterfaces/CommonExampleInterface.h"
  8. #include "../CommonInterfaces/CommonGUIHelperInterface.h"
  9. #include "../SharedMemory/PhysicsServerSharedMemory.h"
  10. #include "../SharedMemory/PhysicsClientC_API.h"
  11. #include <string>
  12. #include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
  13. #include "../Utils/b3Clock.h"
  14. ///quick demo showing the right-handed coordinate system and positive rotations around each axis
  15. class KukaGraspExample : public CommonExampleInterface
  16. {
  17. CommonGraphicsApp* m_app;
  18. GUIHelperInterface* m_guiHelper;
  19. b3RobotSimulatorClientAPI m_robotSim;
  20. int m_kukaIndex;
  21. IKTrajectoryHelper m_ikHelper;
  22. int m_targetSphereInstance;
  23. b3Vector3 m_targetPos;
  24. b3Vector3 m_worldPos;
  25. b3Vector4 m_targetOri;
  26. b3Vector4 m_worldOri;
  27. double m_time;
  28. // int m_options;
  29. b3AlignedObjectArray<int> m_movingInstances;
  30. enum
  31. {
  32. numCubesX = 20,
  33. numCubesY = 20
  34. };
  35. public:
  36. KukaGraspExample(GUIHelperInterface* helper, int /* options */)
  37. : m_app(helper->getAppInterface()),
  38. m_guiHelper(helper),
  39. // m_options(options),
  40. m_kukaIndex(-1),
  41. m_time(0)
  42. {
  43. m_targetPos.setValue(0.5, 0, 1);
  44. m_worldPos.setValue(0, 0, 0);
  45. m_app->setUpAxis(2);
  46. }
  47. virtual ~KukaGraspExample()
  48. {
  49. }
  50. virtual void initPhysics()
  51. {
  52. ///create some graphics proxy for the tracking target
  53. ///the endeffector tries to track it using Inverse Kinematics
  54. {
  55. int sphereId = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_MEDIUM);
  56. b3Quaternion orn(0, 0, 0, 1);
  57. b3Vector4 color = b3MakeVector4(1., 0.3, 0.3, 1);
  58. b3Vector3 scaling = b3MakeVector3(.02, .02, .02);
  59. m_targetSphereInstance = m_app->m_renderer->registerGraphicsInstance(sphereId, m_targetPos, orn, color, scaling);
  60. }
  61. m_app->m_renderer->writeTransforms();
  62. int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
  63. m_robotSim.setGuiHelper(m_guiHelper);
  64. bool connected = m_robotSim.connect(mode);
  65. m_robotSim.configureDebugVisualizer(COV_ENABLE_RGB_BUFFER_PREVIEW, 0);
  66. m_robotSim.configureDebugVisualizer(COV_ENABLE_DEPTH_BUFFER_PREVIEW, 0);
  67. m_robotSim.configureDebugVisualizer(COV_ENABLE_SEGMENTATION_MARK_PREVIEW, 0);
  68. // 0;//m_robotSim.connect(m_guiHelper);
  69. b3Printf("robotSim connected = %d", connected);
  70. {
  71. m_kukaIndex = m_robotSim.loadURDF("kuka_iiwa/model.urdf");
  72. if (m_kukaIndex >= 0)
  73. {
  74. int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
  75. b3Printf("numJoints = %d", numJoints);
  76. for (int i = 0; i < numJoints; i++)
  77. {
  78. b3JointInfo jointInfo;
  79. m_robotSim.getJointInfo(m_kukaIndex, i, &jointInfo);
  80. b3Printf("joint[%d].m_jointName=%s", i, jointInfo.m_jointName);
  81. }
  82. /*
  83. int wheelJointIndices[4]={2,3,6,7};
  84. int wheelTargetVelocities[4]={-10,-10,-10,-10};
  85. for (int i=0;i<4;i++)
  86. {
  87. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  88. controlArgs.m_targetVelocity = wheelTargetVelocities[i];
  89. controlArgs.m_maxTorqueValue = 1e30;
  90. m_robotSim.setJointMotorControl(m_kukaIndex,wheelJointIndices[i],controlArgs);
  91. }
  92. */
  93. }
  94. {
  95. m_robotSim.loadURDF("plane.urdf");
  96. m_robotSim.setGravity(btVector3(0, 0, 0));
  97. }
  98. }
  99. }
  100. virtual void exitPhysics()
  101. {
  102. m_robotSim.disconnect();
  103. }
  104. virtual void stepSimulation(float deltaTime)
  105. {
  106. float dt = deltaTime;
  107. btClamp(dt, 0.0001f, 0.01f);
  108. m_time += dt;
  109. m_targetPos.setValue(0.4 - 0.4 * b3Cos(m_time), 0, 0.8 + 0.4 * b3Cos(m_time));
  110. m_targetOri.setValue(0, 1.0, 0, 0);
  111. m_targetPos.setValue(0.2 * b3Cos(m_time), 0.2 * b3Sin(m_time), 1.1);
  112. int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
  113. if (numJoints == 7)
  114. {
  115. double q_current[7] = {0, 0, 0, 0, 0, 0, 0};
  116. b3JointStates2 jointStates;
  117. if (m_robotSim.getJointStates(m_kukaIndex, jointStates))
  118. {
  119. //skip the base positions (7 values)
  120. b3Assert(7 + numJoints == jointStates.m_numDegreeOfFreedomQ);
  121. for (int i = 0; i < numJoints; i++)
  122. {
  123. q_current[i] = jointStates.m_actualStateQ[i + 7];
  124. }
  125. }
  126. // compute body position and orientation
  127. b3LinkState linkState;
  128. bool computeVelocity = true;
  129. bool computeForwardKinematics = true;
  130. m_robotSim.getLinkState(0, 6, computeVelocity, computeForwardKinematics, &linkState);
  131. m_worldPos.setValue(linkState.m_worldLinkFramePosition[0], linkState.m_worldLinkFramePosition[1], linkState.m_worldLinkFramePosition[2]);
  132. m_worldOri.setValue(linkState.m_worldLinkFrameOrientation[0], linkState.m_worldLinkFrameOrientation[1], linkState.m_worldLinkFrameOrientation[2], linkState.m_worldLinkFrameOrientation[3]);
  133. b3Vector3DoubleData targetPosDataOut;
  134. m_targetPos.serializeDouble(targetPosDataOut);
  135. b3Vector3DoubleData worldPosDataOut;
  136. m_worldPos.serializeDouble(worldPosDataOut);
  137. b3Vector3DoubleData targetOriDataOut;
  138. m_targetOri.serializeDouble(targetOriDataOut);
  139. b3Vector3DoubleData worldOriDataOut;
  140. m_worldOri.serializeDouble(worldOriDataOut);
  141. b3RobotSimulatorInverseKinematicArgs ikargs;
  142. b3RobotSimulatorInverseKinematicsResults ikresults;
  143. ikargs.m_bodyUniqueId = m_kukaIndex;
  144. // ikargs.m_currentJointPositions = q_current;
  145. // ikargs.m_numPositions = 7;
  146. ikargs.m_endEffectorTargetPosition[0] = targetPosDataOut.m_floats[0];
  147. ikargs.m_endEffectorTargetPosition[1] = targetPosDataOut.m_floats[1];
  148. ikargs.m_endEffectorTargetPosition[2] = targetPosDataOut.m_floats[2];
  149. //ikargs.m_flags |= B3_HAS_IK_TARGET_ORIENTATION;
  150. ikargs.m_flags |= B3_HAS_JOINT_DAMPING;
  151. ikargs.m_endEffectorTargetOrientation[0] = targetOriDataOut.m_floats[0];
  152. ikargs.m_endEffectorTargetOrientation[1] = targetOriDataOut.m_floats[1];
  153. ikargs.m_endEffectorTargetOrientation[2] = targetOriDataOut.m_floats[2];
  154. ikargs.m_endEffectorTargetOrientation[3] = targetOriDataOut.m_floats[3];
  155. ikargs.m_endEffectorLinkIndex = 6;
  156. // Settings based on default KUKA arm setting
  157. ikargs.m_lowerLimits.resize(numJoints);
  158. ikargs.m_upperLimits.resize(numJoints);
  159. ikargs.m_jointRanges.resize(numJoints);
  160. ikargs.m_restPoses.resize(numJoints);
  161. ikargs.m_jointDamping.resize(numJoints, 0.5);
  162. ikargs.m_lowerLimits[0] = -2.32;
  163. ikargs.m_lowerLimits[1] = -1.6;
  164. ikargs.m_lowerLimits[2] = -2.32;
  165. ikargs.m_lowerLimits[3] = -1.6;
  166. ikargs.m_lowerLimits[4] = -2.32;
  167. ikargs.m_lowerLimits[5] = -1.6;
  168. ikargs.m_lowerLimits[6] = -2.4;
  169. ikargs.m_upperLimits[0] = 2.32;
  170. ikargs.m_upperLimits[1] = 1.6;
  171. ikargs.m_upperLimits[2] = 2.32;
  172. ikargs.m_upperLimits[3] = 1.6;
  173. ikargs.m_upperLimits[4] = 2.32;
  174. ikargs.m_upperLimits[5] = 1.6;
  175. ikargs.m_upperLimits[6] = 2.4;
  176. ikargs.m_jointRanges[0] = 5.8;
  177. ikargs.m_jointRanges[1] = 4;
  178. ikargs.m_jointRanges[2] = 5.8;
  179. ikargs.m_jointRanges[3] = 4;
  180. ikargs.m_jointRanges[4] = 5.8;
  181. ikargs.m_jointRanges[5] = 4;
  182. ikargs.m_jointRanges[6] = 6;
  183. ikargs.m_restPoses[0] = 0;
  184. ikargs.m_restPoses[1] = 0;
  185. ikargs.m_restPoses[2] = 0;
  186. ikargs.m_restPoses[3] = SIMD_HALF_PI;
  187. ikargs.m_restPoses[4] = 0;
  188. ikargs.m_restPoses[5] = -SIMD_HALF_PI * 0.66;
  189. ikargs.m_restPoses[6] = 0;
  190. ikargs.m_jointDamping[0] = 10.0;
  191. ikargs.m_numDegreeOfFreedom = numJoints;
  192. if (m_robotSim.calculateInverseKinematics(ikargs, ikresults))
  193. {
  194. //copy the IK result to the desired state of the motor/actuator
  195. for (int i = 0; i < numJoints; i++)
  196. {
  197. b3RobotSimulatorJointMotorArgs t(CONTROL_MODE_POSITION_VELOCITY_PD);
  198. t.m_targetPosition = ikresults.m_calculatedJointPositions[i];
  199. t.m_maxTorqueValue = 100.0;
  200. t.m_kp = 1.0;
  201. t.m_targetVelocity = 0;
  202. t.m_kd = 1.0;
  203. m_robotSim.setJointMotorControl(m_kukaIndex, i, t);
  204. }
  205. }
  206. }
  207. m_robotSim.stepSimulation();
  208. }
  209. virtual void renderScene()
  210. {
  211. m_robotSim.renderScene();
  212. b3Quaternion orn(0, 0, 0, 1);
  213. m_app->m_renderer->writeSingleInstanceTransformToCPU(m_targetPos, orn, m_targetSphereInstance);
  214. m_app->m_renderer->writeTransforms();
  215. //draw the end-effector target sphere
  216. //m_app->m_renderer->renderScene();
  217. }
  218. virtual void physicsDebugDraw(int debugDrawMode)
  219. {
  220. m_robotSim.debugDraw(debugDrawMode);
  221. }
  222. virtual bool mouseMoveCallback(float x, float y)
  223. {
  224. return false;
  225. }
  226. virtual bool mouseButtonCallback(int button, int state, float x, float y)
  227. {
  228. return false;
  229. }
  230. virtual bool keyboardCallback(int key, int state)
  231. {
  232. return false;
  233. }
  234. virtual void resetCamera()
  235. {
  236. float dist = 3;
  237. float pitch = -30;
  238. float yaw = 0;
  239. float targetPos[3] = {-0.2, 0.8, 0.3};
  240. if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
  241. {
  242. m_app->m_renderer->getActiveCamera()->setCameraDistance(dist);
  243. m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch);
  244. m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw);
  245. m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0], targetPos[1], targetPos[2]);
  246. }
  247. }
  248. };
  249. class CommonExampleInterface* KukaGraspExampleCreateFunc(struct CommonExampleOptions& options)
  250. {
  251. return new KukaGraspExample(options.m_guiHelper, options.m_option);
  252. }