GripperGraspExample.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470
  1. #include "GripperGraspExample.h"
  2. #include "../CommonInterfaces/CommonGraphicsAppInterface.h"
  3. #include "Bullet3Common/b3Quaternion.h"
  4. #include "Bullet3Common/b3AlignedObjectArray.h"
  5. #include "../CommonInterfaces/CommonRenderInterface.h"
  6. #include "../CommonInterfaces/CommonExampleInterface.h"
  7. #include "../CommonInterfaces/CommonGUIHelperInterface.h"
  8. #include "../SharedMemory/PhysicsServerSharedMemory.h"
  9. #include "../SharedMemory/PhysicsClientC_API.h"
  10. #include "../CommonInterfaces/CommonParameterInterface.h"
  11. #include "../SharedMemory/SharedMemoryPublic.h"
  12. #include <string>
  13. #include "b3RobotSimAPI.h"
  14. #include "../Utils/b3Clock.h"
  15. static btScalar sGripperVerticalVelocity = -0.2f;
  16. static btScalar sGripperClosingTargetVelocity = 0.5f;
  17. class GripperGraspExample : public CommonExampleInterface
  18. {
  19. CommonGraphicsApp* m_app;
  20. GUIHelperInterface* m_guiHelper;
  21. b3RobotSimAPI m_robotSim;
  22. int m_options;
  23. int m_r2d2Index;
  24. int m_gripperIndex;
  25. float m_x;
  26. float m_y;
  27. float m_z;
  28. b3AlignedObjectArray<int> m_movingInstances;
  29. enum
  30. {
  31. numCubesX = 20,
  32. numCubesY = 20
  33. };
  34. public:
  35. GripperGraspExample(GUIHelperInterface* helper, int options)
  36. :m_app(helper->getAppInterface()),
  37. m_guiHelper(helper),
  38. m_options(options),
  39. m_r2d2Index(-1),
  40. m_gripperIndex(-1),
  41. m_x(0),
  42. m_y(0),
  43. m_z(0)
  44. {
  45. m_app->setUpAxis(2);
  46. }
  47. virtual ~GripperGraspExample()
  48. {
  49. m_app->m_renderer->enableBlend(false);
  50. }
  51. virtual void physicsDebugDraw(int debugDrawMode)
  52. {
  53. m_robotSim.debugDraw(debugDrawMode);
  54. }
  55. virtual void initPhysics()
  56. {
  57. bool connected = m_robotSim.connect(m_guiHelper);
  58. b3Printf("robotSim connected = %d",connected);
  59. if ((m_options & eGRIPPER_GRASP)!=0)
  60. {
  61. {
  62. SliderParams slider("Vertical velocity",&sGripperVerticalVelocity);
  63. slider.m_minVal=-2;
  64. slider.m_maxVal=2;
  65. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  66. }
  67. {
  68. SliderParams slider("Closing velocity",&sGripperClosingTargetVelocity
  69. );
  70. slider.m_minVal=-1;
  71. slider.m_maxVal=1;
  72. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  73. }
  74. {
  75. b3RobotSimLoadFileArgs args("");
  76. b3RobotSimLoadFileResults results;
  77. args.m_fileName = "cube_small.urdf";
  78. args.m_startPosition.setValue(0, 0, .107);
  79. args.m_startOrientation.setEulerZYX(0, 0, 0);
  80. args.m_useMultiBody = true;
  81. m_robotSim.loadFile(args, results);
  82. }
  83. {
  84. b3RobotSimLoadFileArgs args("");
  85. args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
  86. args.m_fileType = B3_SDF_FILE;
  87. args.m_useMultiBody = true;
  88. b3RobotSimLoadFileResults results;
  89. if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
  90. {
  91. m_gripperIndex = results.m_uniqueObjectIds[0];
  92. int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
  93. b3Printf("numJoints = %d",numJoints);
  94. for (int i=0;i<numJoints;i++)
  95. {
  96. b3JointInfo jointInfo;
  97. m_robotSim.getJointInfo(m_gripperIndex,i,&jointInfo);
  98. b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
  99. }
  100. /*
  101. int fingerJointIndices[2]={1,3};
  102. double fingerTargetPositions[2]={-0.04,0.04};
  103. for (int i=0;i<2;i++)
  104. {
  105. b3JointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
  106. controlArgs.m_targetPosition = fingerTargetPositions[i];
  107. controlArgs.m_kp = 5.0;
  108. controlArgs.m_kd = 3.0;
  109. controlArgs.m_maxTorqueValue = 1.0;
  110. m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
  111. }
  112. */
  113. int fingerJointIndices[3]={0,1,3};
  114. double fingerTargetVelocities[3]={-0.2,.5,-.5};
  115. double maxTorqueValues[3]={40.0,50.0,50.0};
  116. for (int i=0;i<3;i++)
  117. {
  118. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  119. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  120. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  121. controlArgs.m_kd = 1.;
  122. m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
  123. }
  124. }
  125. }
  126. if (1)
  127. {
  128. b3RobotSimLoadFileArgs args("");
  129. args.m_fileName = "plane.urdf";
  130. args.m_startPosition.setValue(0,0,0);
  131. args.m_startOrientation.setEulerZYX(0,0,0);
  132. args.m_forceOverrideFixedBase = true;
  133. args.m_useMultiBody = true;
  134. b3RobotSimLoadFileResults results;
  135. m_robotSim.loadFile(args,results);
  136. }
  137. m_robotSim.setGravity(b3MakeVector3(0,0,-10));
  138. m_robotSim.setNumSimulationSubSteps(4);
  139. }
  140. if ((m_options & eTWO_POINT_GRASP)!=0)
  141. {
  142. {
  143. b3RobotSimLoadFileArgs args("");
  144. b3RobotSimLoadFileResults results;
  145. args.m_fileName = "cube_small.urdf";
  146. args.m_startPosition.setValue(0, 0, .107);
  147. args.m_startOrientation.setEulerZYX(0, 0, 0);
  148. args.m_useMultiBody = true;
  149. m_robotSim.loadFile(args, results);
  150. }
  151. {
  152. b3RobotSimLoadFileArgs args("");
  153. b3RobotSimLoadFileResults results;
  154. args.m_fileName = "cube_gripper_left.urdf";
  155. args.m_startPosition.setValue(0.068, 0.02, 0.11);
  156. args.m_useMultiBody = true;
  157. m_robotSim.loadFile(args, results);
  158. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  159. controlArgs.m_targetVelocity = -0.1;
  160. controlArgs.m_maxTorqueValue = 10.0;
  161. controlArgs.m_kd = 1.;
  162. m_robotSim.setJointMotorControl(1,0,controlArgs);
  163. }
  164. {
  165. b3RobotSimLoadFileArgs args("");
  166. b3RobotSimLoadFileResults results;
  167. args.m_fileName = "cube_gripper_right.urdf";
  168. args.m_startPosition.setValue(-0.068, 0.02, 0.11);
  169. args.m_useMultiBody = true;
  170. m_robotSim.loadFile(args, results);
  171. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  172. controlArgs.m_targetVelocity = 0.1;
  173. controlArgs.m_maxTorqueValue = 10.0;
  174. controlArgs.m_kd = 1.;
  175. m_robotSim.setJointMotorControl(2,0,controlArgs);
  176. }
  177. if (1)
  178. {
  179. b3RobotSimLoadFileArgs args("");
  180. args.m_fileName = "plane.urdf";
  181. args.m_startPosition.setValue(0,0,0);
  182. args.m_startOrientation.setEulerZYX(0,0,0);
  183. args.m_forceOverrideFixedBase = true;
  184. args.m_useMultiBody = true;
  185. b3RobotSimLoadFileResults results;
  186. m_robotSim.loadFile(args,results);
  187. }
  188. m_robotSim.setGravity(b3MakeVector3(0,0,-10));
  189. m_robotSim.setNumSimulationSubSteps(4);
  190. }
  191. if ((m_options & eONE_MOTOR_GRASP)!=0)
  192. {
  193. {
  194. SliderParams slider("Vertical velocity",&sGripperVerticalVelocity);
  195. slider.m_minVal=-2;
  196. slider.m_maxVal=2;
  197. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  198. }
  199. {
  200. SliderParams slider("Closing velocity",&sGripperClosingTargetVelocity
  201. );
  202. slider.m_minVal=-1;
  203. slider.m_maxVal=1;
  204. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  205. }
  206. {
  207. b3RobotSimLoadFileArgs args("");
  208. b3RobotSimLoadFileResults results;
  209. args.m_fileName = "sphere_small.urdf";
  210. args.m_startPosition.setValue(0, 0, .107);
  211. args.m_startOrientation.setEulerZYX(0, 0, 0);
  212. args.m_useMultiBody = true;
  213. m_robotSim.loadFile(args, results);
  214. }
  215. {
  216. b3RobotSimLoadFileArgs args("");
  217. args.m_fileName = "gripper/wsg50_one_motor_gripper_new.sdf";
  218. args.m_fileType = B3_SDF_FILE;
  219. args.m_useMultiBody = true;
  220. b3RobotSimLoadFileResults results;
  221. if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
  222. {
  223. m_gripperIndex = results.m_uniqueObjectIds[0];
  224. int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
  225. b3Printf("numJoints = %d",numJoints);
  226. for (int i=0;i<numJoints;i++)
  227. {
  228. b3JointInfo jointInfo;
  229. m_robotSim.getJointInfo(m_gripperIndex,i,&jointInfo);
  230. b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
  231. }
  232. for (int i=0;i<8;i++)
  233. {
  234. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  235. controlArgs.m_maxTorqueValue = 0.0;
  236. m_robotSim.setJointMotorControl(m_gripperIndex,i,controlArgs);
  237. }
  238. }
  239. }
  240. if (1)
  241. {
  242. b3RobotSimLoadFileArgs args("");
  243. args.m_fileName = "plane.urdf";
  244. args.m_startPosition.setValue(0,0,0);
  245. args.m_startOrientation.setEulerZYX(0,0,0);
  246. args.m_forceOverrideFixedBase = true;
  247. args.m_useMultiBody = true;
  248. b3RobotSimLoadFileResults results;
  249. m_robotSim.loadFile(args,results);
  250. }
  251. m_robotSim.setGravity(b3MakeVector3(0,0,-10));
  252. /*
  253. b3JointInfo sliderJoint1;
  254. sliderJoint1.m_parentFrame[0] = 0;
  255. sliderJoint1.m_parentFrame[1] = 0;
  256. sliderJoint1.m_parentFrame[2] = 0.06;
  257. sliderJoint1.m_parentFrame[3] = 0;
  258. sliderJoint1.m_parentFrame[4] = 0;
  259. sliderJoint1.m_parentFrame[5] = 0;
  260. sliderJoint1.m_parentFrame[6] = 1.0;
  261. sliderJoint1.m_childFrame[0] = 0;
  262. sliderJoint1.m_childFrame[1] = 0;
  263. sliderJoint1.m_childFrame[2] = 0;
  264. sliderJoint1.m_childFrame[3] = 0;
  265. sliderJoint1.m_childFrame[4] = 0;
  266. sliderJoint1.m_childFrame[5] = 0;
  267. sliderJoint1.m_childFrame[6] = 1.0;
  268. sliderJoint1.m_jointAxis[0] = 1.0;
  269. sliderJoint1.m_jointAxis[1] = 0.0;
  270. sliderJoint1.m_jointAxis[2] = 0.0;
  271. sliderJoint1.m_jointType = ePrismaticType;
  272. b3JointInfo sliderJoint2;
  273. sliderJoint2.m_parentFrame[0] = 0;
  274. sliderJoint2.m_parentFrame[1] = 0;
  275. sliderJoint2.m_parentFrame[2] = 0.06;
  276. sliderJoint2.m_parentFrame[3] = 0;
  277. sliderJoint2.m_parentFrame[4] = 0;
  278. sliderJoint2.m_parentFrame[5] = 0;
  279. sliderJoint2.m_parentFrame[6] = 1.0;
  280. sliderJoint2.m_childFrame[0] = 0;
  281. sliderJoint2.m_childFrame[1] = 0;
  282. sliderJoint2.m_childFrame[2] = 0;
  283. sliderJoint2.m_childFrame[3] = 0;
  284. sliderJoint2.m_childFrame[4] = 0;
  285. sliderJoint2.m_childFrame[5] = 1.0;
  286. sliderJoint2.m_childFrame[6] = 0;
  287. sliderJoint2.m_jointAxis[0] = 1.0;
  288. sliderJoint2.m_jointAxis[1] = 0.0;
  289. sliderJoint2.m_jointAxis[2] = 0.0;
  290. sliderJoint2.m_jointType = ePrismaticType;
  291. m_robotSim.createJoint(1, 0, 1, 3, &sliderJoint1);
  292. m_robotSim.createJoint(1, 0, 1, 6, &sliderJoint2);
  293. */
  294. b3JointInfo revoluteJoint1;
  295. revoluteJoint1.m_parentFrame[0] = -0.055;
  296. revoluteJoint1.m_parentFrame[1] = 0;
  297. revoluteJoint1.m_parentFrame[2] = 0.02;
  298. revoluteJoint1.m_parentFrame[3] = 0;
  299. revoluteJoint1.m_parentFrame[4] = 0;
  300. revoluteJoint1.m_parentFrame[5] = 0;
  301. revoluteJoint1.m_parentFrame[6] = 1.0;
  302. revoluteJoint1.m_childFrame[0] = 0;
  303. revoluteJoint1.m_childFrame[1] = 0;
  304. revoluteJoint1.m_childFrame[2] = 0;
  305. revoluteJoint1.m_childFrame[3] = 0;
  306. revoluteJoint1.m_childFrame[4] = 0;
  307. revoluteJoint1.m_childFrame[5] = 0;
  308. revoluteJoint1.m_childFrame[6] = 1.0;
  309. revoluteJoint1.m_jointAxis[0] = 1.0;
  310. revoluteJoint1.m_jointAxis[1] = 0.0;
  311. revoluteJoint1.m_jointAxis[2] = 0.0;
  312. revoluteJoint1.m_jointType = ePoint2PointType;
  313. b3JointInfo revoluteJoint2;
  314. revoluteJoint2.m_parentFrame[0] = 0.055;
  315. revoluteJoint2.m_parentFrame[1] = 0;
  316. revoluteJoint2.m_parentFrame[2] = 0.02;
  317. revoluteJoint2.m_parentFrame[3] = 0;
  318. revoluteJoint2.m_parentFrame[4] = 0;
  319. revoluteJoint2.m_parentFrame[5] = 0;
  320. revoluteJoint2.m_parentFrame[6] = 1.0;
  321. revoluteJoint2.m_childFrame[0] = 0;
  322. revoluteJoint2.m_childFrame[1] = 0;
  323. revoluteJoint2.m_childFrame[2] = 0;
  324. revoluteJoint2.m_childFrame[3] = 0;
  325. revoluteJoint2.m_childFrame[4] = 0;
  326. revoluteJoint2.m_childFrame[5] = 0;
  327. revoluteJoint2.m_childFrame[6] = 1.0;
  328. revoluteJoint2.m_jointAxis[0] = 1.0;
  329. revoluteJoint2.m_jointAxis[1] = 0.0;
  330. revoluteJoint2.m_jointAxis[2] = 0.0;
  331. revoluteJoint2.m_jointType = ePoint2PointType;
  332. m_robotSim.createJoint(1, 2, 1, 4, &revoluteJoint1);
  333. m_robotSim.createJoint(1, 3, 1, 6, &revoluteJoint2);
  334. }
  335. }
  336. virtual void exitPhysics()
  337. {
  338. m_robotSim.disconnect();
  339. }
  340. virtual void stepSimulation(float deltaTime)
  341. {
  342. if ((m_options & eGRIPPER_GRASP)!=0)
  343. {
  344. if ((m_gripperIndex>=0))
  345. {
  346. int fingerJointIndices[3]={0,1,3};
  347. double fingerTargetVelocities[3]={sGripperVerticalVelocity,sGripperClosingTargetVelocity
  348. ,-sGripperClosingTargetVelocity
  349. };
  350. double maxTorqueValues[3]={40.0,50.0,50.0};
  351. for (int i=0;i<3;i++)
  352. {
  353. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  354. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  355. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  356. controlArgs.m_kd = 1.;
  357. m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
  358. }
  359. }
  360. }
  361. if ((m_options & eONE_MOTOR_GRASP)!=0)
  362. {
  363. int fingerJointIndices[2]={0,1};
  364. double fingerTargetVelocities[2]={sGripperVerticalVelocity,sGripperClosingTargetVelocity
  365. };
  366. double maxTorqueValues[2]={50.0,50.0};
  367. for (int i=0;i<2;i++)
  368. {
  369. b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  370. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  371. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  372. controlArgs.m_kd = 1.;
  373. m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
  374. }
  375. }
  376. m_robotSim.stepSimulation();
  377. }
  378. virtual void renderScene()
  379. {
  380. m_robotSim.renderScene();
  381. //m_app->m_renderer->renderScene();
  382. }
  383. virtual void physicsDebugDraw()
  384. {
  385. }
  386. virtual bool mouseMoveCallback(float x,float y)
  387. {
  388. return false;
  389. }
  390. virtual bool mouseButtonCallback(int button, int state, float x, float y)
  391. {
  392. return false;
  393. }
  394. virtual bool keyboardCallback(int key, int state)
  395. {
  396. return false;
  397. }
  398. virtual void resetCamera()
  399. {
  400. float dist = 1.5;
  401. float pitch = 12;
  402. float yaw = -10;
  403. float targetPos[3]={-0.2,0.8,0.3};
  404. if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
  405. {
  406. m_app->m_renderer->getActiveCamera()->setCameraDistance(dist);
  407. m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch);
  408. m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw);
  409. m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0],targetPos[1],targetPos[2]);
  410. }
  411. }
  412. };
  413. class CommonExampleInterface* GripperGraspExampleCreateFunc(struct CommonExampleOptions& options)
  414. {
  415. return new GripperGraspExample(options.m_guiHelper, options.m_option);
  416. }