RobotControlExample.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669
  1. #include "RobotControlExample.h"
  2. #if 0
  3. #include "../CommonInterfaces/CommonParameterInterface.h"
  4. #include "PhysicsServer.h"
  5. #include "PhysicsClient.h"
  6. #include "SharedMemoryCommon.h"
  7. #include "../Utils/b3Clock.h"
  8. #include "PhysicsClientC_API.h"
  9. #include "../Utils/b3ResourcePath.h"
  10. #include <string>
  11. //const char* blaatnaam = "basename";
  12. struct MyMotorInfo
  13. {
  14. std::string m_jointName;
  15. btScalar m_velTarget;
  16. btScalar m_posTarget;
  17. btScalar m_kp;
  18. btScalar m_kd;
  19. btScalar m_maxForce;
  20. int m_uIndex;
  21. int m_posIndex;
  22. int m_jointIndex;
  23. btScalar m_measuredJointPosition;
  24. btScalar m_measuredJointVelocity;
  25. btVector3 m_measuredJointForce;
  26. btVector3 m_measuredJointTorque;
  27. };
  28. #define MAX_NUM_MOTORS 128
  29. class RobotControlExample : public SharedMemoryCommon
  30. {
  31. PhysicsServerSharedMemory m_physicsServer;
  32. PhysicsClientSharedMemory m_physicsClient;
  33. b3Clock m_realtimeClock;
  34. int m_sequenceNumberGenerator;
  35. bool m_wantsShutdown;
  36. btAlignedObjectArray<SharedMemoryCommand> m_userCommandRequests;
  37. void createButton(const char* name, int id, bool isTrigger );
  38. public:
  39. //@todo, add accessor methods
  40. MyMotorInfo m_motorTargetState[MAX_NUM_MOTORS];
  41. int m_numMotors;
  42. int m_option;
  43. bool m_verboseOutput;
  44. RobotControlExample(GUIHelperInterface* helper, int option);
  45. virtual ~RobotControlExample();
  46. virtual void initPhysics();
  47. virtual void stepSimulation(float deltaTime);
  48. void prepareControlCommand(SharedMemoryCommand& cmd);
  49. void enqueueCommand(const SharedMemoryCommand& orgCommand)
  50. {
  51. m_userCommandRequests.push_back(orgCommand);
  52. SharedMemoryCommand& cmd = m_userCommandRequests[m_userCommandRequests.size()-1];
  53. cmd.m_sequenceNumber = m_sequenceNumberGenerator++;
  54. cmd.m_timeStamp = m_realtimeClock.getTimeMicroseconds();
  55. if (m_verboseOutput)
  56. {
  57. b3Printf("User put command request %d on queue (queue length = %d)\n",cmd.m_type, m_userCommandRequests.size());
  58. }
  59. }
  60. virtual void resetCamera()
  61. {
  62. float dist = 5;
  63. float pitch = 50;
  64. float yaw = 35;
  65. float targetPos[3]={0,0,0};//-3,2.8,-2.5};
  66. m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
  67. }
  68. virtual bool wantsTermination();
  69. virtual bool isConnected();
  70. virtual void renderScene()
  71. {
  72. m_physicsServer.renderScene();
  73. }
  74. virtual void exitPhysics(){}
  75. virtual void physicsDebugDraw(int debugFlags)
  76. {
  77. m_physicsServer.physicsDebugDraw(debugFlags);
  78. }
  79. virtual bool mouseMoveCallback(float x,float y){return false;};
  80. virtual bool mouseButtonCallback(int button, int state, float x, float y){return false;}
  81. virtual bool keyboardCallback(int key, int state){return false;}
  82. virtual void setSharedMemoryKey(int key)
  83. {
  84. m_physicsServer.setSharedMemoryKey(key);
  85. m_physicsClient.setSharedMemoryKey(key);
  86. }
  87. };
  88. bool RobotControlExample::isConnected()
  89. {
  90. return m_physicsClient.isConnected();
  91. }
  92. void MyCallback2(int buttonId, bool buttonState, void* userPtr)
  93. {
  94. RobotControlExample* cl = (RobotControlExample*) userPtr;
  95. SharedMemoryCommand command;
  96. switch (buttonId)
  97. {
  98. case CMD_LOAD_URDF:
  99. {
  100. command.m_type =CMD_LOAD_URDF;
  101. command.m_updateFlags = URDF_ARGS_FILE_NAME|URDF_ARGS_INITIAL_POSITION|URDF_ARGS_INITIAL_ORIENTATION;
  102. sprintf(command.m_urdfArguments.m_urdfFileName,"r2d2.urdf");//kuka_lwr/kuka.urdf");//r2d2.urdf");
  103. command.m_urdfArguments.m_initialPosition[0] = 0.0;
  104. command.m_urdfArguments.m_initialPosition[1] = 0.0;
  105. command.m_urdfArguments.m_initialPosition[2] = 0.0;
  106. command.m_urdfArguments.m_initialOrientation[0] = 0.0;
  107. command.m_urdfArguments.m_initialOrientation[1] = 0.0;
  108. command.m_urdfArguments.m_initialOrientation[2] = 0.0;
  109. command.m_urdfArguments.m_initialOrientation[3] = 1.0;
  110. command.m_urdfArguments.m_useFixedBase = false;
  111. command.m_urdfArguments.m_useMultiBody = true;
  112. cl->enqueueCommand(command);
  113. break;
  114. }
  115. case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS:
  116. {
  117. //#ifdef USE_C_API
  118. b3InitPhysicsParamCommand(&command);
  119. b3PhysicsParamSetGravity(&command, 1,1,-10);
  120. // #else
  121. //
  122. // command.m_type = CMD_SEND_PHYSICS_SIMULATION_PARAMETERS;
  123. // command.m_physSimParamArgs.m_gravityAcceleration[0] = 0;
  124. // command.m_physSimParamArgs.m_gravityAcceleration[1] = 0;
  125. // command.m_physSimParamArgs.m_gravityAcceleration[2] = -10;
  126. // command.m_physSimParamArgs.m_updateFlags = SIM_PARAM_UPDATE_GRAVITY;
  127. // #endif // USE_C_API
  128. cl->enqueueCommand(command);
  129. break;
  130. };
  131. case CMD_INIT_POSE:
  132. {
  133. ///@todo: implement this
  134. command.m_type = CMD_INIT_POSE;
  135. cl->enqueueCommand(command);
  136. break;
  137. }
  138. case CMD_CREATE_BOX_COLLISION_SHAPE:
  139. {
  140. command.m_type =CMD_CREATE_BOX_COLLISION_SHAPE;
  141. command.m_updateFlags = BOX_SHAPE_HAS_INITIAL_POSITION;
  142. command.m_createBoxShapeArguments.m_initialPosition[0] = 0;
  143. command.m_createBoxShapeArguments.m_initialPosition[1] = 0;
  144. command.m_createBoxShapeArguments.m_initialPosition[2] = -3;
  145. cl->enqueueCommand(command);
  146. break;
  147. }
  148. case CMD_REQUEST_ACTUAL_STATE:
  149. {
  150. command.m_type =CMD_REQUEST_ACTUAL_STATE;
  151. cl->enqueueCommand(command);
  152. break;
  153. };
  154. case CMD_STEP_FORWARD_SIMULATION:
  155. {
  156. command.m_type =CMD_STEP_FORWARD_SIMULATION;
  157. cl->enqueueCommand(command);
  158. break;
  159. }
  160. case CMD_SEND_DESIRED_STATE:
  161. {
  162. command.m_type =CMD_SEND_DESIRED_STATE;
  163. cl->prepareControlCommand(command);
  164. cl->enqueueCommand(command);
  165. break;
  166. }
  167. case CMD_SEND_BULLET_DATA_STREAM:
  168. {
  169. command.m_type = buttonId;
  170. sprintf(command.m_dataStreamArguments.m_bulletFileName,"slope.bullet");
  171. command.m_dataStreamArguments.m_streamChunkLength = 0;
  172. cl->enqueueCommand(command);
  173. break;
  174. }
  175. default:
  176. {
  177. b3Error("Unknown buttonId");
  178. btAssert(0);
  179. }
  180. };
  181. }
  182. void RobotControlExample::prepareControlCommand(SharedMemoryCommand& command)
  183. {
  184. for (int i=0;i<MAX_DEGREE_OF_FREEDOM;i++)
  185. {
  186. command.m_sendDesiredStateCommandArgument.m_desiredStateQdot[i] = 0;
  187. command.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[i] = 0;
  188. }
  189. switch (m_option)
  190. {
  191. case ROBOT_VELOCITY_CONTROL:
  192. {
  193. command.m_sendDesiredStateCommandArgument.m_controlMode = CONTROL_MODE_VELOCITY;
  194. for (int i=0;i<MAX_DEGREE_OF_FREEDOM;i++)
  195. {
  196. command.m_sendDesiredStateCommandArgument.m_desiredStateQdot[i] = 0;
  197. command.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[i] = 1000;
  198. }
  199. for (int i=0;i<m_numMotors;i++)
  200. {
  201. btScalar targetVel = m_motorTargetState[i].m_velTarget;
  202. int uIndex = m_motorTargetState[i].m_uIndex;
  203. command.m_sendDesiredStateCommandArgument.m_desiredStateQdot[uIndex] = targetVel;
  204. }
  205. break;
  206. }
  207. case ROBOT_PD_CONTROL:
  208. {
  209. command.m_sendDesiredStateCommandArgument.m_controlMode = CONTROL_MODE_POSITION_VELOCITY_PD;
  210. for (int i=0;i<m_numMotors;i++)
  211. {
  212. int uIndex = m_motorTargetState[i].m_uIndex;
  213. command.m_sendDesiredStateCommandArgument.m_Kp[uIndex] = m_motorTargetState[i].m_kp;
  214. command.m_sendDesiredStateCommandArgument.m_Kd[uIndex] = m_motorTargetState[i].m_kd;
  215. command.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[uIndex] = 10000;//max force
  216. btScalar targetVel = m_motorTargetState[i].m_velTarget;
  217. command.m_sendDesiredStateCommandArgument.m_desiredStateQdot[uIndex] = targetVel;
  218. int posIndex = m_motorTargetState[i].m_posIndex;
  219. btScalar targetPos = m_motorTargetState[i].m_posTarget;
  220. command.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex] = targetPos;
  221. }
  222. break;
  223. }
  224. case ROBOT_PING_PONG_JOINT_FEEDBACK:
  225. {
  226. command.m_sendDesiredStateCommandArgument.m_controlMode = CONTROL_MODE_VELOCITY;
  227. for (int i=0;i<MAX_DEGREE_OF_FREEDOM;i++)
  228. {
  229. command.m_sendDesiredStateCommandArgument.m_desiredStateQdot[i] = 0;
  230. command.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[i] = 1000;
  231. }
  232. for (int i=0;i<m_numMotors;i++)
  233. {
  234. btScalar targetVel = m_motorTargetState[i].m_velTarget;
  235. int uIndex = m_motorTargetState[i].m_uIndex;
  236. command.m_sendDesiredStateCommandArgument.m_desiredStateQdot[uIndex] = m_motorTargetState[i].m_velTarget;
  237. }
  238. break;
  239. }
  240. default:
  241. {
  242. b3Warning("Unknown control mode in RobotControlExample::prepareControlCommand");
  243. }
  244. };
  245. }
  246. void RobotControlExample::createButton(const char* name, int buttonId, bool isTrigger )
  247. {
  248. ButtonParams button(name,buttonId, isTrigger);
  249. button.m_callback = MyCallback2;
  250. button.m_userPointer = this;
  251. m_guiHelper->getParameterInterface()->registerButtonParameter(button);
  252. }
  253. RobotControlExample::RobotControlExample(GUIHelperInterface* helper, int option)
  254. :SharedMemoryCommon(helper),
  255. m_wantsShutdown(false),
  256. m_sequenceNumberGenerator(0),
  257. m_numMotors(0),
  258. m_option(option),
  259. m_verboseOutput(false)
  260. {
  261. bool useServer = true;
  262. }
  263. RobotControlExample::~RobotControlExample()
  264. {
  265. bool deInitializeSharedMemory = true;
  266. m_physicsClient.disconnectSharedMemory();
  267. m_physicsServer.disconnectSharedMemory(deInitializeSharedMemory);
  268. }
  269. void RobotControlExample::initPhysics()
  270. {
  271. ///for this testing we use Z-axis up
  272. int upAxis = 2;
  273. m_guiHelper->setUpAxis(upAxis);
  274. /* createEmptyDynamicsWorld();
  275. //todo: create a special debug drawer that will cache the lines, so we can send the debug info over the wire
  276. m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
  277. btVector3 grav(0,0,0);
  278. grav[upAxis] = 0;//-9.8;
  279. this->m_dynamicsWorld->setGravity(grav);
  280. */
  281. m_physicsServer.connectSharedMemory( m_guiHelper);
  282. if (m_guiHelper && m_guiHelper->getParameterInterface())
  283. {
  284. bool isTrigger = false;
  285. createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
  286. createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
  287. createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger);
  288. createButton("Get State",CMD_REQUEST_ACTUAL_STATE, isTrigger);
  289. createButton("Send Desired State",CMD_SEND_DESIRED_STATE, isTrigger);
  290. createButton("Create Box Collider",CMD_CREATE_BOX_COLLISION_SHAPE,isTrigger);
  291. createButton("Set Physics Params",CMD_SEND_PHYSICS_SIMULATION_PARAMETERS,isTrigger);
  292. createButton("Init Pose",CMD_INIT_POSE,isTrigger);
  293. } else
  294. {
  295. /*
  296. m_userCommandRequests.push_back(CMD_LOAD_URDF);
  297. m_userCommandRequests.push_back(CMD_REQUEST_ACTUAL_STATE);
  298. m_userCommandRequests.push_back(CMD_SEND_DESIRED_STATE);
  299. m_userCommandRequests.push_back(CMD_REQUEST_ACTUAL_STATE);
  300. //m_userCommandRequests.push_back(CMD_SET_JOINT_FEEDBACK);
  301. m_userCommandRequests.push_back(CMD_CREATE_BOX_COLLISION_SHAPE);
  302. //m_userCommandRequests.push_back(CMD_CREATE_RIGID_BODY);
  303. m_userCommandRequests.push_back(CMD_STEP_FORWARD_SIMULATION);
  304. m_userCommandRequests.push_back(CMD_REQUEST_ACTUAL_STATE);
  305. m_userCommandRequests.push_back(CMD_SHUTDOWN);
  306. */
  307. }
  308. if (!m_physicsClient.connect())
  309. {
  310. b3Warning("Cannot eonnect to physics client");
  311. }
  312. }
  313. bool RobotControlExample::wantsTermination()
  314. {
  315. return m_wantsShutdown;
  316. }
  317. void RobotControlExample::stepSimulation(float deltaTime)
  318. {
  319. m_physicsServer.processClientCommands();
  320. if (m_physicsClient.isConnected())
  321. {
  322. SharedMemoryStatus status;
  323. bool hasStatus = m_physicsClient.processServerStatus(status);
  324. if ((m_option==ROBOT_PING_PONG_JOINT_FEEDBACK) && hasStatus && status.m_type == CMD_ACTUAL_STATE_UPDATE_COMPLETED)
  325. {
  326. //update sensor feedback: joint force/torque data and measured joint positions
  327. for (int i=0;i<m_numMotors;i++)
  328. {
  329. int jointIndex = m_motorTargetState[i].m_jointIndex;
  330. int positionIndex = m_motorTargetState[i].m_posIndex;
  331. int velocityIndex = m_motorTargetState[i].m_uIndex;
  332. m_motorTargetState[i].m_measuredJointPosition = status.m_sendActualStateArgs.m_actualStateQ[positionIndex];
  333. m_motorTargetState[i].m_measuredJointVelocity = status.m_sendActualStateArgs.m_actualStateQdot[velocityIndex];
  334. m_motorTargetState[i].m_measuredJointForce.setValue(status.m_sendActualStateArgs.m_jointReactionForces[6*jointIndex],
  335. status.m_sendActualStateArgs.m_jointReactionForces[6*jointIndex+1],
  336. status.m_sendActualStateArgs.m_jointReactionForces[6*jointIndex+2]);
  337. m_motorTargetState[i].m_measuredJointTorque.setValue(status.m_sendActualStateArgs.m_jointReactionForces[6*jointIndex+3],
  338. status.m_sendActualStateArgs.m_jointReactionForces[6*jointIndex+4],
  339. status.m_sendActualStateArgs.m_jointReactionForces[6*jointIndex+5]);
  340. if (m_motorTargetState[i].m_measuredJointPosition>0.1)
  341. {
  342. m_motorTargetState[i].m_velTarget = -1.5;
  343. } else
  344. {
  345. m_motorTargetState[i].m_velTarget = 1.5;
  346. }
  347. b3Printf("Joint Force (Linear) [%s]=(%f,%f,%f)\n",m_motorTargetState[i].m_jointName.c_str(),m_motorTargetState[i].m_measuredJointForce.x(),m_motorTargetState[i].m_measuredJointForce.y(),m_motorTargetState[i].m_measuredJointForce.z());
  348. b3Printf("Joint Torque (Angular) [%s]=(%f,%f,%f)\n",m_motorTargetState[i].m_jointName.c_str(),m_motorTargetState[i].m_measuredJointTorque.x(),m_motorTargetState[i].m_measuredJointTorque.y(),m_motorTargetState[i].m_measuredJointTorque.z());
  349. }
  350. }
  351. if (hasStatus && status.m_type == CMD_URDF_LOADING_COMPLETED)
  352. {
  353. SharedMemoryCommand sensorCommand;
  354. sensorCommand.m_type = CMD_CREATE_SENSOR;
  355. sensorCommand.m_createSensorArguments.m_numJointSensorChanges = 0;
  356. for (int jointIndex=0;jointIndex<m_physicsClient.getNumJoints();jointIndex++)
  357. {
  358. b3JointInfo info;
  359. m_physicsClient.getJointInfo(jointIndex,info);
  360. if (m_verboseOutput)
  361. {
  362. b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex);
  363. }
  364. if (info.m_flags & JOINT_HAS_MOTORIZED_POWER)
  365. {
  366. if (m_numMotors<MAX_NUM_MOTORS)
  367. {
  368. switch (m_option)
  369. {
  370. case ROBOT_VELOCITY_CONTROL:
  371. {
  372. char motorName[1024];
  373. sprintf(motorName,"%s q'", info.m_jointName);
  374. MyMotorInfo* motorInfo = &m_motorTargetState[m_numMotors];
  375. motorInfo->m_jointName = info.m_jointName;
  376. motorInfo->m_velTarget = 0.f;
  377. motorInfo->m_posTarget = 0.f;
  378. motorInfo->m_uIndex = info.m_uIndex;
  379. SliderParams slider(motorName,&motorInfo->m_velTarget);
  380. slider.m_minVal=-4;
  381. slider.m_maxVal=4;
  382. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  383. m_numMotors++;
  384. break;
  385. }
  386. case ROBOT_PD_CONTROL:
  387. {
  388. char motorName[1024];
  389. MyMotorInfo* motorInfo = &m_motorTargetState[m_numMotors];
  390. motorInfo->m_jointName = info.m_jointName;
  391. motorInfo->m_velTarget = 0.f;
  392. motorInfo->m_posTarget = 0.f;
  393. motorInfo->m_uIndex = info.m_uIndex;
  394. motorInfo->m_posIndex = info.m_qIndex;
  395. motorInfo->m_kp = 1;
  396. motorInfo->m_kd = 0;
  397. {
  398. sprintf(motorName,"%s kp", info.m_jointName);
  399. SliderParams slider(motorName,&motorInfo->m_kp);
  400. slider.m_minVal=0;
  401. slider.m_maxVal=1;
  402. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  403. }
  404. {
  405. sprintf(motorName,"%s q", info.m_jointName);
  406. SliderParams slider(motorName,&motorInfo->m_posTarget);
  407. slider.m_minVal=-SIMD_PI;
  408. slider.m_maxVal=SIMD_PI;
  409. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  410. }
  411. {
  412. sprintf(motorName,"%s kd", info.m_jointName);
  413. SliderParams slider(motorName,&motorInfo->m_kd);
  414. slider.m_minVal=0;
  415. slider.m_maxVal=1;
  416. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  417. }
  418. {
  419. sprintf(motorName,"%s q'", info.m_jointName);
  420. SliderParams slider(motorName,&motorInfo->m_velTarget);
  421. slider.m_minVal=-10;
  422. slider.m_maxVal=10;
  423. m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
  424. }
  425. m_numMotors++;
  426. break;
  427. }
  428. case ROBOT_PING_PONG_JOINT_FEEDBACK:
  429. {
  430. if (info.m_flags & JOINT_HAS_MOTORIZED_POWER)
  431. {
  432. if (m_numMotors<MAX_NUM_MOTORS)
  433. {
  434. MyMotorInfo* motorInfo = &m_motorTargetState[m_numMotors];
  435. motorInfo->m_jointName = info.m_jointName;
  436. motorInfo->m_velTarget = 0.f;
  437. motorInfo->m_posTarget = 0.f;
  438. motorInfo->m_uIndex = info.m_uIndex;
  439. motorInfo->m_posIndex = info.m_qIndex;
  440. motorInfo->m_jointIndex = jointIndex;
  441. sensorCommand.m_createSensorArguments.m_sensorType[sensorCommand.m_createSensorArguments.m_numJointSensorChanges] = SENSOR_FORCE_TORQUE;
  442. sensorCommand.m_createSensorArguments.m_jointIndex[sensorCommand.m_createSensorArguments.m_numJointSensorChanges] = jointIndex;
  443. sensorCommand.m_createSensorArguments.m_enableJointForceSensor[sensorCommand.m_createSensorArguments.m_numJointSensorChanges] = true;
  444. sensorCommand.m_createSensorArguments.m_numJointSensorChanges++;
  445. m_numMotors++;
  446. }
  447. }
  448. break;
  449. }
  450. default:
  451. {
  452. b3Warning("Unknown control mode in RobotControlExample::stepSimulation");
  453. }
  454. };
  455. }
  456. }
  457. }
  458. if (sensorCommand.m_createSensorArguments.m_numJointSensorChanges)
  459. {
  460. enqueueCommand(sensorCommand);
  461. }
  462. }
  463. if (m_physicsClient.canSubmitCommand())
  464. {
  465. if (m_userCommandRequests.size())
  466. {
  467. if (m_verboseOutput)
  468. {
  469. b3Printf("Outstanding user command requests: %d\n", m_userCommandRequests.size());
  470. }
  471. SharedMemoryCommand cmd = m_userCommandRequests[0];
  472. //a manual 'pop_front', we don't use 'remove' because it will re-order the commands
  473. for (int i=1;i<m_userCommandRequests.size();i++)
  474. {
  475. m_userCommandRequests[i-1] = m_userCommandRequests[i];
  476. }
  477. m_userCommandRequests.pop_back();
  478. if (cmd.m_type == CMD_CREATE_SENSOR)
  479. {
  480. b3Printf("CMD_CREATE_SENSOR!\n");
  481. }
  482. if (cmd.m_type == CMD_SEND_BULLET_DATA_STREAM)
  483. {
  484. char relativeFileName[1024];
  485. bool fileFound = b3ResourcePath::findResourcePath(cmd.m_dataStreamArguments.m_bulletFileName,relativeFileName,1024);
  486. if (fileFound)
  487. {
  488. FILE *fp = fopen(relativeFileName, "rb");
  489. if (fp)
  490. {
  491. fseek(fp, 0L, SEEK_END);
  492. int mFileLen = ftell(fp);
  493. fseek(fp, 0L, SEEK_SET);
  494. if (mFileLen<SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE)
  495. {
  496. char* data = (char*)malloc(mFileLen);
  497. fread(data, mFileLen, 1, fp);
  498. fclose(fp);
  499. cmd.m_dataStreamArguments.m_streamChunkLength = mFileLen;
  500. m_physicsClient.uploadBulletFileToSharedMemory(data,mFileLen);
  501. if (m_verboseOutput)
  502. {
  503. b3Printf("Loaded bullet data chunks into shared memory\n");
  504. }
  505. free(data);
  506. } else
  507. {
  508. b3Warning("Bullet file size (%d) exceeds of streaming memory chunk size (%d)\n", mFileLen,SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
  509. }
  510. } else
  511. {
  512. b3Warning("Cannot open file %s\n", relativeFileName);
  513. }
  514. } else
  515. {
  516. b3Warning("Cannot find file %s\n", cmd.m_dataStreamArguments.m_bulletFileName);
  517. }
  518. }
  519. m_physicsClient.submitClientCommand(cmd);
  520. } else
  521. {
  522. if (m_numMotors)
  523. {
  524. SharedMemoryCommand command;
  525. command.m_type =CMD_SEND_DESIRED_STATE;
  526. prepareControlCommand(command);
  527. enqueueCommand(command);
  528. command.m_type =CMD_STEP_FORWARD_SIMULATION;
  529. enqueueCommand(command);
  530. command.m_type = CMD_REQUEST_ACTUAL_STATE;
  531. enqueueCommand(command);
  532. }
  533. }
  534. }
  535. }
  536. }
  537. extern int gSharedMemoryKey;
  538. class CommonExampleInterface* RobotControlExampleCreateFunc(struct CommonExampleOptions& options)
  539. {
  540. RobotControlExample* example = new RobotControlExample(options.m_guiHelper, options.m_option);
  541. if (gSharedMemoryKey>=0)
  542. {
  543. example->setSharedMemoryKey(gSharedMemoryKey);
  544. }
  545. return example;
  546. }
  547. #endif