GripperGraspExample.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742
  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 "../RobotSimulator/b3RobotSimulatorClientAPI.h"
  14. #include "../Utils/b3Clock.h"
  15. static btScalar sGripperVerticalVelocity = 0.f;
  16. static btScalar sGripperClosingTargetVelocity = -0.7f;
  17. class GripperGraspExample : public CommonExampleInterface
  18. {
  19. CommonGraphicsApp* m_app;
  20. GUIHelperInterface* m_guiHelper;
  21. b3RobotSimulatorClientAPI m_robotSim;
  22. int m_options;
  23. int m_gripperIndex;
  24. double m_time;
  25. b3Vector3 m_targetPos;
  26. b3Vector3 m_worldPos;
  27. b3Vector4 m_targetOri;
  28. b3Vector4 m_worldOri;
  29. b3AlignedObjectArray<int> m_movingInstances;
  30. enum
  31. {
  32. numCubesX = 20,
  33. numCubesY = 20
  34. };
  35. public:
  36. GripperGraspExample(GUIHelperInterface* helper, int options)
  37. : m_app(helper->getAppInterface()),
  38. m_guiHelper(helper),
  39. m_options(options),
  40. m_gripperIndex(-1)
  41. {
  42. m_app->setUpAxis(2);
  43. }
  44. virtual ~GripperGraspExample()
  45. {
  46. }
  47. virtual void physicsDebugDraw(int debugDrawMode)
  48. {
  49. m_robotSim.debugDraw(debugDrawMode);
  50. }
  51. virtual void initPhysics()
  52. {
  53. int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
  54. m_robotSim.setGuiHelper(m_guiHelper);
  55. bool connected = m_robotSim.connect(mode);
  56. m_robotSim.configureDebugVisualizer(COV_ENABLE_RGB_BUFFER_PREVIEW, 0);
  57. m_robotSim.configureDebugVisualizer(COV_ENABLE_DEPTH_BUFFER_PREVIEW, 0);
  58. m_robotSim.configureDebugVisualizer(COV_ENABLE_SEGMENTATION_MARK_PREVIEW, 0);
  59. b3Printf("robotSim connected = %d", connected);
  60. if ((m_options & eGRIPPER_GRASP) != 0)
  61. {
  62. {
  63. SliderParams slider("Vertical velocity", &sGripperVerticalVelocity);
  64. slider.m_minVal = -2;
  65. slider.m_maxVal = 2;
  66. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  67. }
  68. {
  69. SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity);
  70. slider.m_minVal = -1;
  71. slider.m_maxVal = 1;
  72. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  73. }
  74. {
  75. b3RobotSimulatorLoadUrdfFileArgs args;
  76. args.m_startPosition.setValue(0, 0, .107);
  77. args.m_startOrientation.setEulerZYX(0, 0, 0);
  78. args.m_useMultiBody = true;
  79. m_robotSim.loadURDF("cube_small.urdf", args);
  80. }
  81. {
  82. b3RobotSimulatorLoadFileResults results;
  83. m_robotSim.loadSDF("gripper/wsg50_with_r2d2_gripper.sdf", results);
  84. if (results.m_uniqueObjectIds.size() == 1)
  85. {
  86. m_gripperIndex = results.m_uniqueObjectIds[0];
  87. int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
  88. b3Printf("numJoints = %d", numJoints);
  89. for (int i = 0; i < numJoints; i++)
  90. {
  91. b3JointInfo jointInfo;
  92. m_robotSim.getJointInfo(m_gripperIndex, i, &jointInfo);
  93. b3Printf("joint[%d].m_jointName=%s", i, jointInfo.m_jointName);
  94. }
  95. /*
  96. int fingerJointIndices[2]={1,3};
  97. double fingerTargetPositions[2]={-0.04,0.04};
  98. for (int i=0;i<2;i++)
  99. {
  100. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
  101. controlArgs.m_targetPosition = fingerTargetPositions[i];
  102. controlArgs.m_kp = 5.0;
  103. controlArgs.m_kd = 3.0;
  104. controlArgs.m_maxTorqueValue = 1.0;
  105. m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
  106. }
  107. */
  108. int fingerJointIndices[3] = {0, 1, 3};
  109. double fingerTargetVelocities[3] = {-0.2, .5, -.5};
  110. double maxTorqueValues[3] = {40.0, 50.0, 50.0};
  111. for (int i = 0; i < 3; i++)
  112. {
  113. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  114. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  115. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  116. controlArgs.m_kd = 1.;
  117. m_robotSim.setJointMotorControl(m_gripperIndex, fingerJointIndices[i], controlArgs);
  118. }
  119. }
  120. }
  121. if (1)
  122. {
  123. m_robotSim.loadURDF("plane.urdf");
  124. }
  125. m_robotSim.setGravity(btVector3(0, 0, -10));
  126. m_robotSim.setNumSimulationSubSteps(4);
  127. }
  128. if ((m_options & eTWO_POINT_GRASP) != 0)
  129. {
  130. {
  131. b3RobotSimulatorLoadUrdfFileArgs args;
  132. args.m_startPosition.setValue(0, 0, .107);
  133. m_robotSim.loadURDF("cube_small.urdf", args);
  134. }
  135. {
  136. b3RobotSimulatorLoadUrdfFileArgs args;
  137. args.m_startPosition.setValue(0.068, 0.02, 0.11);
  138. m_robotSim.loadURDF("cube_gripper_left.urdf", args);
  139. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  140. controlArgs.m_targetVelocity = -0.1;
  141. controlArgs.m_maxTorqueValue = 10.0;
  142. controlArgs.m_kd = 1.;
  143. m_robotSim.setJointMotorControl(1, 0, controlArgs);
  144. }
  145. {
  146. b3RobotSimulatorLoadUrdfFileArgs args;
  147. args.m_startPosition.setValue(-0.068, 0.02, 0.11);
  148. m_robotSim.loadURDF("cube_gripper_right.urdf", args);
  149. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  150. controlArgs.m_targetVelocity = 0.1;
  151. controlArgs.m_maxTorqueValue = 10.0;
  152. controlArgs.m_kd = 1.;
  153. m_robotSim.setJointMotorControl(2, 0, controlArgs);
  154. }
  155. if (1)
  156. {
  157. m_robotSim.loadURDF("plane.urdf");
  158. }
  159. m_robotSim.setGravity(btVector3(0, 0, -10));
  160. m_robotSim.setNumSimulationSubSteps(4);
  161. }
  162. if ((m_options & eONE_MOTOR_GRASP) != 0)
  163. {
  164. m_robotSim.setNumSolverIterations(150);
  165. {
  166. SliderParams slider("Vertical velocity", &sGripperVerticalVelocity);
  167. slider.m_minVal = -2;
  168. slider.m_maxVal = 2;
  169. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  170. }
  171. {
  172. SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity);
  173. slider.m_minVal = -1;
  174. slider.m_maxVal = 1;
  175. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  176. }
  177. {
  178. b3RobotSimulatorLoadUrdfFileArgs args;
  179. args.m_startPosition.setValue(0, -0.2, .47);
  180. args.m_startOrientation.setEulerZYX(SIMD_HALF_PI, 0, 0);
  181. m_robotSim.loadURDF("dinnerware/pan_tefal.urdf", args);
  182. }
  183. {
  184. b3RobotSimulatorLoadFileResults args;
  185. b3RobotSimulatorLoadFileResults results;
  186. m_robotSim.loadSDF("gripper/wsg50_one_motor_gripper_new.sdf", results);
  187. if (results.m_uniqueObjectIds.size() == 1)
  188. {
  189. m_gripperIndex = results.m_uniqueObjectIds[0];
  190. int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
  191. b3Printf("numJoints = %d", numJoints);
  192. for (int i = 0; i < numJoints; i++)
  193. {
  194. b3JointInfo jointInfo;
  195. m_robotSim.getJointInfo(m_gripperIndex, i, &jointInfo);
  196. b3Printf("joint[%d].m_jointName=%s", i, jointInfo.m_jointName);
  197. }
  198. for (int i = 0; i < 8; i++)
  199. {
  200. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  201. controlArgs.m_maxTorqueValue = 0.0;
  202. m_robotSim.setJointMotorControl(m_gripperIndex, i, controlArgs);
  203. }
  204. }
  205. }
  206. if (1)
  207. {
  208. m_robotSim.loadURDF("plane.urdf");
  209. }
  210. m_robotSim.setGravity(btVector3(0, 0, -10));
  211. b3JointInfo revoluteJoint1;
  212. revoluteJoint1.m_parentFrame[0] = -0.055;
  213. revoluteJoint1.m_parentFrame[1] = 0;
  214. revoluteJoint1.m_parentFrame[2] = 0.02;
  215. revoluteJoint1.m_parentFrame[3] = 0;
  216. revoluteJoint1.m_parentFrame[4] = 0;
  217. revoluteJoint1.m_parentFrame[5] = 0;
  218. revoluteJoint1.m_parentFrame[6] = 1.0;
  219. revoluteJoint1.m_childFrame[0] = 0;
  220. revoluteJoint1.m_childFrame[1] = 0;
  221. revoluteJoint1.m_childFrame[2] = 0;
  222. revoluteJoint1.m_childFrame[3] = 0;
  223. revoluteJoint1.m_childFrame[4] = 0;
  224. revoluteJoint1.m_childFrame[5] = 0;
  225. revoluteJoint1.m_childFrame[6] = 1.0;
  226. revoluteJoint1.m_jointAxis[0] = 1.0;
  227. revoluteJoint1.m_jointAxis[1] = 0.0;
  228. revoluteJoint1.m_jointAxis[2] = 0.0;
  229. revoluteJoint1.m_jointType = ePoint2PointType;
  230. b3JointInfo revoluteJoint2;
  231. revoluteJoint2.m_parentFrame[0] = 0.055;
  232. revoluteJoint2.m_parentFrame[1] = 0;
  233. revoluteJoint2.m_parentFrame[2] = 0.02;
  234. revoluteJoint2.m_parentFrame[3] = 0;
  235. revoluteJoint2.m_parentFrame[4] = 0;
  236. revoluteJoint2.m_parentFrame[5] = 0;
  237. revoluteJoint2.m_parentFrame[6] = 1.0;
  238. revoluteJoint2.m_childFrame[0] = 0;
  239. revoluteJoint2.m_childFrame[1] = 0;
  240. revoluteJoint2.m_childFrame[2] = 0;
  241. revoluteJoint2.m_childFrame[3] = 0;
  242. revoluteJoint2.m_childFrame[4] = 0;
  243. revoluteJoint2.m_childFrame[5] = 0;
  244. revoluteJoint2.m_childFrame[6] = 1.0;
  245. revoluteJoint2.m_jointAxis[0] = 1.0;
  246. revoluteJoint2.m_jointAxis[1] = 0.0;
  247. revoluteJoint2.m_jointAxis[2] = 0.0;
  248. revoluteJoint2.m_jointType = ePoint2PointType;
  249. m_robotSim.createConstraint(1, 2, 1, 4, &revoluteJoint1);
  250. m_robotSim.createConstraint(1, 3, 1, 6, &revoluteJoint2);
  251. }
  252. if ((m_options & eGRASP_SOFT_BODY) != 0)
  253. {
  254. {
  255. SliderParams slider("Vertical velocity", &sGripperVerticalVelocity);
  256. slider.m_minVal = -2;
  257. slider.m_maxVal = 2;
  258. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  259. }
  260. {
  261. SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity);
  262. slider.m_minVal = -1;
  263. slider.m_maxVal = 1;
  264. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  265. }
  266. {
  267. b3RobotSimulatorLoadFileResults results;
  268. m_robotSim.loadSDF("gripper/wsg50_one_motor_gripper_new.sdf", results);
  269. if (results.m_uniqueObjectIds.size() == 1)
  270. {
  271. m_gripperIndex = results.m_uniqueObjectIds[0];
  272. int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
  273. b3Printf("numJoints = %d", numJoints);
  274. for (int i = 0; i < numJoints; i++)
  275. {
  276. b3JointInfo jointInfo;
  277. m_robotSim.getJointInfo(m_gripperIndex, i, &jointInfo);
  278. b3Printf("joint[%d].m_jointName=%s", i, jointInfo.m_jointName);
  279. }
  280. for (int i = 0; i < 8; i++)
  281. {
  282. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  283. controlArgs.m_maxTorqueValue = 0.0;
  284. m_robotSim.setJointMotorControl(m_gripperIndex, i, controlArgs);
  285. }
  286. }
  287. }
  288. {
  289. b3RobotSimulatorLoadUrdfFileArgs args;
  290. args.m_startPosition.setValue(0, 0, -0.2);
  291. args.m_startOrientation.setEulerZYX(0, 0, 0);
  292. m_robotSim.loadURDF("plane.urdf", args);
  293. }
  294. m_robotSim.setGravity(btVector3(0, 0, -10));
  295. b3RobotSimulatorLoadSoftBodyArgs args(0.1, 1, 0.02);
  296. args.m_startPosition.setValue(0, 0, 5);
  297. args.m_startOrientation.setValue(1, 0, 0, 1);
  298. m_robotSim.loadSoftBody("bunny.obj", args);
  299. b3JointInfo revoluteJoint1;
  300. revoluteJoint1.m_parentFrame[0] = -0.055;
  301. revoluteJoint1.m_parentFrame[1] = 0;
  302. revoluteJoint1.m_parentFrame[2] = 0.02;
  303. revoluteJoint1.m_parentFrame[3] = 0;
  304. revoluteJoint1.m_parentFrame[4] = 0;
  305. revoluteJoint1.m_parentFrame[5] = 0;
  306. revoluteJoint1.m_parentFrame[6] = 1.0;
  307. revoluteJoint1.m_childFrame[0] = 0;
  308. revoluteJoint1.m_childFrame[1] = 0;
  309. revoluteJoint1.m_childFrame[2] = 0;
  310. revoluteJoint1.m_childFrame[3] = 0;
  311. revoluteJoint1.m_childFrame[4] = 0;
  312. revoluteJoint1.m_childFrame[5] = 0;
  313. revoluteJoint1.m_childFrame[6] = 1.0;
  314. revoluteJoint1.m_jointAxis[0] = 1.0;
  315. revoluteJoint1.m_jointAxis[1] = 0.0;
  316. revoluteJoint1.m_jointAxis[2] = 0.0;
  317. revoluteJoint1.m_jointType = ePoint2PointType;
  318. b3JointInfo revoluteJoint2;
  319. revoluteJoint2.m_parentFrame[0] = 0.055;
  320. revoluteJoint2.m_parentFrame[1] = 0;
  321. revoluteJoint2.m_parentFrame[2] = 0.02;
  322. revoluteJoint2.m_parentFrame[3] = 0;
  323. revoluteJoint2.m_parentFrame[4] = 0;
  324. revoluteJoint2.m_parentFrame[5] = 0;
  325. revoluteJoint2.m_parentFrame[6] = 1.0;
  326. revoluteJoint2.m_childFrame[0] = 0;
  327. revoluteJoint2.m_childFrame[1] = 0;
  328. revoluteJoint2.m_childFrame[2] = 0;
  329. revoluteJoint2.m_childFrame[3] = 0;
  330. revoluteJoint2.m_childFrame[4] = 0;
  331. revoluteJoint2.m_childFrame[5] = 0;
  332. revoluteJoint2.m_childFrame[6] = 1.0;
  333. revoluteJoint2.m_jointAxis[0] = 1.0;
  334. revoluteJoint2.m_jointAxis[1] = 0.0;
  335. revoluteJoint2.m_jointAxis[2] = 0.0;
  336. revoluteJoint2.m_jointType = ePoint2PointType;
  337. m_robotSim.createConstraint(0, 2, 0, 4, &revoluteJoint1);
  338. m_robotSim.createConstraint(0, 3, 0, 6, &revoluteJoint2);
  339. }
  340. if ((m_options & eGRASP_DEFORMABLE_CLOTH) != 0)
  341. {
  342. m_robotSim.resetSimulation(RESET_USE_DEFORMABLE_WORLD);
  343. {
  344. SliderParams slider("Vertical velocity", &sGripperVerticalVelocity);
  345. slider.m_minVal = -2;
  346. slider.m_maxVal = 2;
  347. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  348. }
  349. {
  350. SliderParams slider("Closing velocity", &sGripperClosingTargetVelocity);
  351. slider.m_minVal = -1;
  352. slider.m_maxVal = 1;
  353. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  354. }
  355. {
  356. b3RobotSimulatorLoadFileResults results;
  357. m_robotSim.loadSDF("gripper/wsg50_one_motor_gripper_new.sdf", results);
  358. if (results.m_uniqueObjectIds.size() == 1)
  359. {
  360. m_gripperIndex = results.m_uniqueObjectIds[0];
  361. int numJoints = m_robotSim.getNumJoints(m_gripperIndex);
  362. b3Printf("numJoints = %d", numJoints);
  363. for (int i = 0; i < numJoints; i++)
  364. {
  365. b3JointInfo jointInfo;
  366. m_robotSim.getJointInfo(m_gripperIndex, i, &jointInfo);
  367. b3Printf("joint[%d].m_jointName=%s", i, jointInfo.m_jointName);
  368. }
  369. for (int i = 0; i < 8; i++)
  370. {
  371. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  372. controlArgs.m_maxTorqueValue = 0.0;
  373. m_robotSim.setJointMotorControl(m_gripperIndex, i, controlArgs);
  374. }
  375. }
  376. }
  377. {
  378. b3RobotSimulatorLoadUrdfFileArgs args;
  379. args.m_startPosition.setValue(0, 0, -0.2);
  380. args.m_startOrientation.setEulerZYX(0, 0, 0);
  381. m_robotSim.loadURDF("plane.urdf", args);
  382. }
  383. m_robotSim.setGravity(btVector3(0, 0, -10));
  384. m_robotSim.setGravity(btVector3(0, 0, -10));
  385. b3RobotSimulatorLoadDeformableBodyArgs args(2, .01, 0.006);
  386. args.m_springElasticStiffness = 1;
  387. args.m_springDampingStiffness = .01;
  388. args.m_springBendingStiffness = .1;
  389. args.m_frictionCoeff = 10;
  390. args.m_useSelfCollision = false;
  391. args.m_useFaceContact = true;
  392. args.m_useBendingSprings = true;
  393. args.m_startPosition.setValue(0, 0, 0);
  394. args.m_startOrientation.setValue(0, 0, 1, 1);
  395. //m_robotSim.loadDeformableBody("flat_napkin.obj", args);
  396. b3JointInfo revoluteJoint1;
  397. revoluteJoint1.m_parentFrame[0] = -0.055;
  398. revoluteJoint1.m_parentFrame[1] = 0;
  399. revoluteJoint1.m_parentFrame[2] = 0.02;
  400. revoluteJoint1.m_parentFrame[3] = 0;
  401. revoluteJoint1.m_parentFrame[4] = 0;
  402. revoluteJoint1.m_parentFrame[5] = 0;
  403. revoluteJoint1.m_parentFrame[6] = 1.0;
  404. revoluteJoint1.m_childFrame[0] = 0;
  405. revoluteJoint1.m_childFrame[1] = 0;
  406. revoluteJoint1.m_childFrame[2] = 0;
  407. revoluteJoint1.m_childFrame[3] = 0;
  408. revoluteJoint1.m_childFrame[4] = 0;
  409. revoluteJoint1.m_childFrame[5] = 0;
  410. revoluteJoint1.m_childFrame[6] = 1.0;
  411. revoluteJoint1.m_jointAxis[0] = 1.0;
  412. revoluteJoint1.m_jointAxis[1] = 0.0;
  413. revoluteJoint1.m_jointAxis[2] = 0.0;
  414. revoluteJoint1.m_jointType = ePoint2PointType;
  415. b3JointInfo revoluteJoint2;
  416. revoluteJoint2.m_parentFrame[0] = 0.055;
  417. revoluteJoint2.m_parentFrame[1] = 0;
  418. revoluteJoint2.m_parentFrame[2] = 0.02;
  419. revoluteJoint2.m_parentFrame[3] = 0;
  420. revoluteJoint2.m_parentFrame[4] = 0;
  421. revoluteJoint2.m_parentFrame[5] = 0;
  422. revoluteJoint2.m_parentFrame[6] = 1.0;
  423. revoluteJoint2.m_childFrame[0] = 0;
  424. revoluteJoint2.m_childFrame[1] = 0;
  425. revoluteJoint2.m_childFrame[2] = 0;
  426. revoluteJoint2.m_childFrame[3] = 0;
  427. revoluteJoint2.m_childFrame[4] = 0;
  428. revoluteJoint2.m_childFrame[5] = 0;
  429. revoluteJoint2.m_childFrame[6] = 1.0;
  430. revoluteJoint2.m_jointAxis[0] = 1.0;
  431. revoluteJoint2.m_jointAxis[1] = 0.0;
  432. revoluteJoint2.m_jointAxis[2] = 0.0;
  433. revoluteJoint2.m_jointType = ePoint2PointType;
  434. m_robotSim.createConstraint(0, 2, 0, 4, &revoluteJoint1);
  435. m_robotSim.createConstraint(0, 3, 0, 6, &revoluteJoint2);
  436. m_robotSim.setNumSimulationSubSteps(2);
  437. }
  438. if ((m_options & eSOFTBODY_MULTIBODY_COUPLING) != 0)
  439. {
  440. {
  441. b3RobotSimulatorLoadUrdfFileArgs args;
  442. args.m_startPosition.setValue(-0.5, 0, 0.1);
  443. args.m_startOrientation.setEulerZYX(0, 0, 0);
  444. args.m_forceOverrideFixedBase = true;
  445. args.m_useMultiBody = true;
  446. int kukaId = m_robotSim.loadURDF("kuka_iiwa/model.urdf", args);
  447. int numJoints = m_robotSim.getNumJoints(kukaId);
  448. b3Printf("numJoints = %d", numJoints);
  449. for (int i = 0; i < numJoints; i++)
  450. {
  451. b3JointInfo jointInfo;
  452. m_robotSim.getJointInfo(kukaId, i, &jointInfo);
  453. b3Printf("joint[%d].m_jointName=%s", i, jointInfo.m_jointName);
  454. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  455. controlArgs.m_maxTorqueValue = 500.0;
  456. m_robotSim.setJointMotorControl(kukaId, i, controlArgs);
  457. }
  458. }
  459. {
  460. b3RobotSimulatorLoadUrdfFileArgs args;
  461. args.m_startPosition.setValue(0, 0, 0);
  462. args.m_startOrientation.setEulerZYX(0, 0, 0);
  463. args.m_forceOverrideFixedBase = true;
  464. args.m_useMultiBody = false;
  465. m_robotSim.loadURDF("plane.urdf", args);
  466. }
  467. m_robotSim.setGravity(btVector3(0, 0, -10));
  468. b3RobotSimulatorLoadSoftBodyArgs args(0.3, 10, 0.1);
  469. m_robotSim.loadSoftBody("bunny.obj", args);
  470. }
  471. }
  472. virtual void exitPhysics()
  473. {
  474. m_robotSim.disconnect();
  475. }
  476. virtual void stepSimulation(float deltaTime)
  477. {
  478. if ((m_options & eGRIPPER_GRASP) != 0)
  479. {
  480. if ((m_gripperIndex >= 0))
  481. {
  482. int fingerJointIndices[3] = {0, 1, 3};
  483. double fingerTargetVelocities[3] = {sGripperVerticalVelocity, sGripperClosingTargetVelocity, -sGripperClosingTargetVelocity};
  484. double maxTorqueValues[3] = {40.0, 50.0, 50.0};
  485. for (int i = 0; i < 3; i++)
  486. {
  487. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  488. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  489. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  490. controlArgs.m_kd = 1.;
  491. m_robotSim.setJointMotorControl(m_gripperIndex, fingerJointIndices[i], controlArgs);
  492. }
  493. }
  494. }
  495. if ((m_options & eONE_MOTOR_GRASP) != 0)
  496. {
  497. int fingerJointIndices[2] = {0, 1};
  498. double fingerTargetVelocities[2] = {sGripperVerticalVelocity, sGripperClosingTargetVelocity};
  499. double maxTorqueValues[2] = {800.0, 800.0};
  500. for (int i = 0; i < 2; i++)
  501. {
  502. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  503. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  504. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  505. controlArgs.m_kd = 1.;
  506. m_robotSim.setJointMotorControl(m_gripperIndex, fingerJointIndices[i], controlArgs);
  507. }
  508. }
  509. if ((m_options & eGRASP_SOFT_BODY) != 0)
  510. {
  511. int fingerJointIndices[2] = {0, 1};
  512. double fingerTargetVelocities[2] = {sGripperVerticalVelocity, sGripperClosingTargetVelocity};
  513. double maxTorqueValues[2] = {50.0, 10.0};
  514. for (int i = 0; i < 2; i++)
  515. {
  516. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  517. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  518. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  519. controlArgs.m_kd = 1.;
  520. m_robotSim.setJointMotorControl(m_gripperIndex, fingerJointIndices[i], controlArgs);
  521. }
  522. }
  523. if ((m_options & eGRASP_DEFORMABLE_CLOTH) != 0)
  524. {
  525. int fingerJointIndices[2] = {0, 1};
  526. double fingerTargetVelocities[2] = {sGripperVerticalVelocity, sGripperClosingTargetVelocity};
  527. double maxTorqueValues[2] = {250.0, 50.0};
  528. for (int i = 0; i < 2; i++)
  529. {
  530. b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
  531. controlArgs.m_targetVelocity = fingerTargetVelocities[i];
  532. controlArgs.m_maxTorqueValue = maxTorqueValues[i];
  533. controlArgs.m_kd = 1.;
  534. m_robotSim.setJointMotorControl(m_gripperIndex, fingerJointIndices[i], controlArgs);
  535. }
  536. }
  537. if ((m_options & eSOFTBODY_MULTIBODY_COUPLING) != 0)
  538. {
  539. float dt = deltaTime;
  540. btClamp(dt, 0.0001f, 0.01f);
  541. m_time += dt;
  542. m_targetPos.setValue(0, 0, 0.5 + 0.2 * b3Cos(m_time));
  543. m_targetOri.setValue(0, 1.0, 0, 0);
  544. int numJoints = m_robotSim.getNumJoints(0);
  545. if (numJoints == 7)
  546. {
  547. double q_current[7] = {0, 0, 0, 0, 0, 0, 0};
  548. b3JointStates2 jointStates;
  549. if (m_robotSim.getJointStates(0, jointStates))
  550. {
  551. //skip the base positions (7 values)
  552. b3Assert(7 + numJoints == jointStates.m_numDegreeOfFreedomQ);
  553. for (int i = 0; i < numJoints; i++)
  554. {
  555. q_current[i] = jointStates.m_actualStateQ[i + 7];
  556. }
  557. }
  558. // compute body position and orientation
  559. b3LinkState linkState;
  560. bool computeVelocity = true;
  561. bool computeForwardKinematics = true;
  562. m_robotSim.getLinkState(0, 6, computeVelocity, computeForwardKinematics, &linkState);
  563. m_worldPos.setValue(linkState.m_worldLinkFramePosition[0], linkState.m_worldLinkFramePosition[1], linkState.m_worldLinkFramePosition[2]);
  564. m_worldOri.setValue(linkState.m_worldLinkFrameOrientation[0], linkState.m_worldLinkFrameOrientation[1], linkState.m_worldLinkFrameOrientation[2], linkState.m_worldLinkFrameOrientation[3]);
  565. b3Vector3DoubleData targetPosDataOut;
  566. m_targetPos.serializeDouble(targetPosDataOut);
  567. b3Vector3DoubleData worldPosDataOut;
  568. m_worldPos.serializeDouble(worldPosDataOut);
  569. b3Vector3DoubleData targetOriDataOut;
  570. m_targetOri.serializeDouble(targetOriDataOut);
  571. b3Vector3DoubleData worldOriDataOut;
  572. m_worldOri.serializeDouble(worldOriDataOut);
  573. b3RobotSimulatorInverseKinematicArgs ikargs;
  574. b3RobotSimulatorInverseKinematicsResults ikresults;
  575. ikargs.m_bodyUniqueId = 0;
  576. // ikargs.m_currentJointPositions = q_current;
  577. // ikargs.m_numPositions = 7;
  578. ikargs.m_endEffectorTargetPosition[0] = targetPosDataOut.m_floats[0];
  579. ikargs.m_endEffectorTargetPosition[1] = targetPosDataOut.m_floats[1];
  580. ikargs.m_endEffectorTargetPosition[2] = targetPosDataOut.m_floats[2];
  581. ikargs.m_flags |= B3_HAS_IK_TARGET_ORIENTATION /* + B3_HAS_NULL_SPACE_VELOCITY*/;
  582. ikargs.m_endEffectorTargetOrientation[0] = targetOriDataOut.m_floats[0];
  583. ikargs.m_endEffectorTargetOrientation[1] = targetOriDataOut.m_floats[1];
  584. ikargs.m_endEffectorTargetOrientation[2] = targetOriDataOut.m_floats[2];
  585. ikargs.m_endEffectorTargetOrientation[3] = targetOriDataOut.m_floats[3];
  586. ikargs.m_endEffectorLinkIndex = 6;
  587. // Settings based on default KUKA arm setting
  588. ikargs.m_lowerLimits.resize(numJoints);
  589. ikargs.m_upperLimits.resize(numJoints);
  590. ikargs.m_jointRanges.resize(numJoints);
  591. ikargs.m_restPoses.resize(numJoints);
  592. ikargs.m_lowerLimits[0] = -2.32;
  593. ikargs.m_lowerLimits[1] = -1.6;
  594. ikargs.m_lowerLimits[2] = -2.32;
  595. ikargs.m_lowerLimits[3] = -1.6;
  596. ikargs.m_lowerLimits[4] = -2.32;
  597. ikargs.m_lowerLimits[5] = -1.6;
  598. ikargs.m_lowerLimits[6] = -2.4;
  599. ikargs.m_upperLimits[0] = 2.32;
  600. ikargs.m_upperLimits[1] = 1.6;
  601. ikargs.m_upperLimits[2] = 2.32;
  602. ikargs.m_upperLimits[3] = 1.6;
  603. ikargs.m_upperLimits[4] = 2.32;
  604. ikargs.m_upperLimits[5] = 1.6;
  605. ikargs.m_upperLimits[6] = 2.4;
  606. ikargs.m_jointRanges[0] = 5.8;
  607. ikargs.m_jointRanges[1] = 4;
  608. ikargs.m_jointRanges[2] = 5.8;
  609. ikargs.m_jointRanges[3] = 4;
  610. ikargs.m_jointRanges[4] = 5.8;
  611. ikargs.m_jointRanges[5] = 4;
  612. ikargs.m_jointRanges[6] = 6;
  613. ikargs.m_restPoses[0] = 0;
  614. ikargs.m_restPoses[1] = 0;
  615. ikargs.m_restPoses[2] = 0;
  616. ikargs.m_restPoses[3] = SIMD_HALF_PI;
  617. ikargs.m_restPoses[4] = 0;
  618. ikargs.m_restPoses[5] = -SIMD_HALF_PI * 0.66;
  619. ikargs.m_restPoses[6] = 0;
  620. ikargs.m_numDegreeOfFreedom = numJoints;
  621. if (m_robotSim.calculateInverseKinematics(ikargs, ikresults))
  622. {
  623. //copy the IK result to the desired state of the motor/actuator
  624. for (int i = 0; i < numJoints; i++)
  625. {
  626. b3RobotSimulatorJointMotorArgs t(CONTROL_MODE_POSITION_VELOCITY_PD);
  627. t.m_targetPosition = ikresults.m_calculatedJointPositions[i];
  628. t.m_maxTorqueValue = 100.0;
  629. t.m_kp = 1.0;
  630. t.m_targetVelocity = 0;
  631. t.m_kd = 1.0;
  632. m_robotSim.setJointMotorControl(0, i, t);
  633. }
  634. }
  635. }
  636. }
  637. m_robotSim.stepSimulation();
  638. }
  639. virtual void renderScene()
  640. {
  641. m_robotSim.renderScene();
  642. //m_app->m_renderer->renderScene();
  643. }
  644. virtual bool mouseMoveCallback(float x, float y)
  645. {
  646. return m_robotSim.mouseMoveCallback(x, y);
  647. }
  648. virtual bool mouseButtonCallback(int button, int state, float x, float y)
  649. {
  650. return m_robotSim.mouseButtonCallback(button, state, x, y);
  651. }
  652. virtual bool keyboardCallback(int key, int state)
  653. {
  654. return false;
  655. }
  656. virtual void resetCamera()
  657. {
  658. float dist = 1.5;
  659. float pitch = -10;
  660. float yaw = 18;
  661. float targetPos[3] = {-0.2, 0.8, 0.3};
  662. if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
  663. {
  664. m_app->m_renderer->getActiveCamera()->setCameraDistance(dist);
  665. m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch);
  666. m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw);
  667. m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0], targetPos[1], targetPos[2]);
  668. }
  669. }
  670. };
  671. class CommonExampleInterface* GripperGraspExampleCreateFunc(struct CommonExampleOptions& options)
  672. {
  673. return new GripperGraspExample(options.m_guiHelper, options.m_option);
  674. }