KukaGraspExample.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319
  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 "b3RobotSimAPI.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. b3RobotSimAPI 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. m_app->m_renderer->enableBlend(false);
  50. }
  51. virtual void physicsDebugDraw(int debugDrawMode)
  52. {
  53. }
  54. virtual void initPhysics()
  55. {
  56. ///create some graphics proxy for the tracking target
  57. ///the endeffector tries to track it using Inverse Kinematics
  58. {
  59. int sphereId = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_MEDIUM);
  60. b3Quaternion orn(0, 0, 0, 1);
  61. b3Vector4 color = b3MakeVector4(1., 0.3, 0.3, 1);
  62. b3Vector3 scaling = b3MakeVector3(.02, .02, .02);
  63. m_targetSphereInstance = m_app->m_renderer->registerGraphicsInstance(sphereId, m_targetPos, orn, color, scaling);
  64. }
  65. m_app->m_renderer->writeTransforms();
  66. bool connected = m_robotSim.connect(m_guiHelper);
  67. b3Printf("robotSim connected = %d",connected);
  68. {
  69. b3RobotSimLoadFileArgs args("");
  70. args.m_fileName = "kuka_iiwa/model.urdf";
  71. args.m_startPosition.setValue(0,0,0);
  72. b3RobotSimLoadFileResults results;
  73. if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
  74. {
  75. m_kukaIndex = results.m_uniqueObjectIds[0];
  76. int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
  77. b3Printf("numJoints = %d",numJoints);
  78. for (int i=0;i<numJoints;i++)
  79. {
  80. b3JointInfo jointInfo;
  81. m_robotSim.getJointInfo(m_kukaIndex,i,&jointInfo);
  82. b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
  83. }
  84. /*
  85. int wheelJointIndices[4]={2,3,6,7};
  86. int wheelTargetVelocities[4]={-10,-10,-10,-10};
  87. for (int i=0;i<4;i++)
  88. {
  89. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  90. controlArgs.m_targetVelocity = wheelTargetVelocities[i];
  91. controlArgs.m_maxTorqueValue = 1e30;
  92. m_robotSim.setJointMotorControl(m_kukaIndex,wheelJointIndices[i],controlArgs);
  93. }
  94. */
  95. }
  96. if (0)
  97. {
  98. b3RobotSimLoadFileArgs args("");
  99. args.m_fileName = "kiva_shelf/model.sdf";
  100. args.m_forceOverrideFixedBase = true;
  101. args.m_fileType = B3_SDF_FILE;
  102. args.m_startOrientation = b3Quaternion(0,0,0,1);
  103. b3RobotSimLoadFileResults results;
  104. m_robotSim.loadFile(args,results);
  105. }
  106. {
  107. b3RobotSimLoadFileArgs args("");
  108. args.m_fileName = "plane.urdf";
  109. args.m_startPosition.setValue(0,0,0);
  110. args.m_forceOverrideFixedBase = true;
  111. b3RobotSimLoadFileResults results;
  112. m_robotSim.loadFile(args,results);
  113. m_robotSim.setGravity(b3MakeVector3(0,0,0));
  114. }
  115. }
  116. }
  117. virtual void exitPhysics()
  118. {
  119. m_robotSim.disconnect();
  120. }
  121. virtual void stepSimulation(float deltaTime)
  122. {
  123. float dt = deltaTime;
  124. btClamp(dt,0.0001f,0.01f);
  125. m_time+=dt;
  126. m_targetPos.setValue(0.4-0.4*b3Cos( m_time), 0, 0.8+0.4*b3Cos( m_time));
  127. m_targetOri.setValue(0, 1.0, 0, 0);
  128. int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
  129. if (numJoints==7)
  130. {
  131. double q_current[7]={0,0,0,0,0,0,0};
  132. double world_position[3]={0,0,0};
  133. double world_orientation[4]={0,0,0,0};
  134. b3JointStates jointStates;
  135. if (m_robotSim.getJointStates(m_kukaIndex,jointStates))
  136. {
  137. //skip the base positions (7 values)
  138. b3Assert(7+numJoints == jointStates.m_numDegreeOfFreedomQ);
  139. for (int i=0;i<numJoints;i++)
  140. {
  141. q_current[i] = jointStates.m_actualStateQ[i+7];
  142. }
  143. }
  144. // compute body position and orientation
  145. m_robotSim.getLinkState(0, 6, world_position, world_orientation);
  146. m_worldPos.setValue(world_position[0], world_position[1], world_position[2]);
  147. m_worldOri.setValue(world_orientation[0], world_orientation[1], world_orientation[2], world_orientation[3]);
  148. b3Vector3DoubleData targetPosDataOut;
  149. m_targetPos.serializeDouble(targetPosDataOut);
  150. b3Vector3DoubleData worldPosDataOut;
  151. m_worldPos.serializeDouble(worldPosDataOut);
  152. b3Vector3DoubleData targetOriDataOut;
  153. m_targetOri.serializeDouble(targetOriDataOut);
  154. b3Vector3DoubleData worldOriDataOut;
  155. m_worldOri.serializeDouble(worldOriDataOut);
  156. b3RobotSimInverseKinematicArgs ikargs;
  157. b3RobotSimInverseKinematicsResults ikresults;
  158. ikargs.m_bodyUniqueId = m_kukaIndex;
  159. // ikargs.m_currentJointPositions = q_current;
  160. // ikargs.m_numPositions = 7;
  161. ikargs.m_endEffectorTargetPosition[0] = targetPosDataOut.m_floats[0];
  162. ikargs.m_endEffectorTargetPosition[1] = targetPosDataOut.m_floats[1];
  163. ikargs.m_endEffectorTargetPosition[2] = targetPosDataOut.m_floats[2];
  164. ikargs.m_flags |= /*B3_HAS_IK_TARGET_ORIENTATION +*/ B3_HAS_NULL_SPACE_VELOCITY;
  165. ikargs.m_endEffectorTargetOrientation[0] = targetOriDataOut.m_floats[0];
  166. ikargs.m_endEffectorTargetOrientation[1] = targetOriDataOut.m_floats[1];
  167. ikargs.m_endEffectorTargetOrientation[2] = targetOriDataOut.m_floats[2];
  168. ikargs.m_endEffectorTargetOrientation[3] = targetOriDataOut.m_floats[3];
  169. ikargs.m_endEffectorLinkIndex = 6;
  170. // Settings based on default KUKA arm setting
  171. ikargs.m_lowerLimits.resize(numJoints);
  172. ikargs.m_upperLimits.resize(numJoints);
  173. ikargs.m_jointRanges.resize(numJoints);
  174. ikargs.m_restPoses.resize(numJoints);
  175. ikargs.m_lowerLimits[0] = -2.32;
  176. ikargs.m_lowerLimits[1] = -1.6;
  177. ikargs.m_lowerLimits[2] = -2.32;
  178. ikargs.m_lowerLimits[3] = -1.6;
  179. ikargs.m_lowerLimits[4] = -2.32;
  180. ikargs.m_lowerLimits[5] = -1.6;
  181. ikargs.m_lowerLimits[6] = -2.4;
  182. ikargs.m_upperLimits[0] = 2.32;
  183. ikargs.m_upperLimits[1] = 1.6;
  184. ikargs.m_upperLimits[2] = 2.32;
  185. ikargs.m_upperLimits[3] = 1.6;
  186. ikargs.m_upperLimits[4] = 2.32;
  187. ikargs.m_upperLimits[5] = 1.6;
  188. ikargs.m_upperLimits[6] = 2.4;
  189. ikargs.m_jointRanges[0] = 5.8;
  190. ikargs.m_jointRanges[1] = 4;
  191. ikargs.m_jointRanges[2] = 5.8;
  192. ikargs.m_jointRanges[3] = 4;
  193. ikargs.m_jointRanges[4] = 5.8;
  194. ikargs.m_jointRanges[5] = 4;
  195. ikargs.m_jointRanges[6] = 6;
  196. ikargs.m_restPoses[0] = 0;
  197. ikargs.m_restPoses[1] = 0;
  198. ikargs.m_restPoses[2] = 0;
  199. ikargs.m_restPoses[3] = SIMD_HALF_PI;
  200. ikargs.m_restPoses[4] = 0;
  201. ikargs.m_restPoses[5] = -SIMD_HALF_PI*0.66;
  202. ikargs.m_restPoses[6] = 0;
  203. ikargs.m_numDegreeOfFreedom = numJoints;
  204. if (m_robotSim.calculateInverseKinematics(ikargs,ikresults))
  205. {
  206. //copy the IK result to the desired state of the motor/actuator
  207. for (int i=0;i<numJoints;i++)
  208. {
  209. b3JointMotorArgs t(CONTROL_MODE_POSITION_VELOCITY_PD);
  210. t.m_targetPosition = ikresults.m_calculatedJointPositions[i];
  211. t.m_maxTorqueValue = 100.0;
  212. t.m_kp= 1.0;
  213. t.m_targetVelocity = 0;
  214. t.m_kd = 1.0;
  215. m_robotSim.setJointMotorControl(m_kukaIndex,i,t);
  216. }
  217. }
  218. }
  219. m_robotSim.stepSimulation();
  220. }
  221. virtual void renderScene()
  222. {
  223. m_robotSim.renderScene();
  224. b3Quaternion orn(0, 0, 0, 1);
  225. m_app->m_renderer->writeSingleInstanceTransformToCPU(m_targetPos, orn, m_targetSphereInstance);
  226. m_app->m_renderer->writeTransforms();
  227. //draw the end-effector target sphere
  228. //m_app->m_renderer->renderScene();
  229. }
  230. virtual void physicsDebugDraw()
  231. {
  232. }
  233. virtual bool mouseMoveCallback(float x,float y)
  234. {
  235. return false;
  236. }
  237. virtual bool mouseButtonCallback(int button, int state, float x, float y)
  238. {
  239. return false;
  240. }
  241. virtual bool keyboardCallback(int key, int state)
  242. {
  243. return false;
  244. }
  245. virtual void resetCamera()
  246. {
  247. float dist = 3;
  248. float pitch = 0;
  249. float yaw = 30;
  250. float targetPos[3]={-0.2,0.8,0.3};
  251. if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
  252. {
  253. m_app->m_renderer->getActiveCamera()->setCameraDistance(dist);
  254. m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch);
  255. m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw);
  256. m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0],targetPos[1],targetPos[2]);
  257. }
  258. }
  259. };
  260. class CommonExampleInterface* KukaGraspExampleCreateFunc(struct CommonExampleOptions& options)
  261. {
  262. return new KukaGraspExample(options.m_guiHelper, options.m_option);
  263. }