RobotControlExample.cpp 20 KB

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