@@ -301,6 +301,12 @@ struct CommandLogPlayback
301
301
}
302
302
};
303
303
304
+ struct SaveWorldObjectData
305
+ {
306
+ b3AlignedObjectArray<int > m_bodyUniqueIds;
307
+ std::string m_fileName;
308
+ };
309
+
304
310
struct PhysicsServerCommandProcessorInternalData
305
311
{
306
312
// /handle management
@@ -410,7 +416,7 @@ struct PhysicsServerCommandProcessorInternalData
410
416
btAlignedObjectArray<btMultiBodyJointFeedback*> m_multiBodyJointFeedbacks;
411
417
btHashMap<btHashPtr, btInverseDynamics::MultiBodyTree*> m_inverseDynamicsBodies;
412
418
btHashMap<btHashPtr, IKTrajectoryHelper*> m_inverseKinematicsHelpers;
413
-
419
+ b3AlignedObjectArray<SaveWorldObjectData> m_saveWorldBodyData;
414
420
415
421
416
422
btAlignedObjectArray<btBulletWorldImporter*> m_worldImporters;
@@ -811,6 +817,9 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
811
817
{
812
818
b3Printf (" loaded %s OK!" , fileName);
813
819
}
820
+ SaveWorldObjectData sd;
821
+ sd.m_fileName = fileName;
822
+
814
823
815
824
for (int m =0 ; m<u2b.getNumModels ();m++)
816
825
{
@@ -824,6 +833,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
824
833
825
834
InternalBodyHandle* bodyHandle = m_data->getHandle (bodyUniqueId);
826
835
836
+ sd.m_bodyUniqueIds .push_back (bodyUniqueId);
827
837
828
838
u2b.setBodyUniqueId (bodyUniqueId);
829
839
{
@@ -854,6 +864,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
854
864
if (mb)
855
865
mb->setUserIndex2 (bodyUniqueId);
856
866
867
+
857
868
if (mb)
858
869
{
859
870
bodyHandle->m_multiBody = mb;
@@ -898,6 +909,9 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
898
909
}
899
910
900
911
}
912
+
913
+ m_data->m_saveWorldBodyData .push_back (sd);
914
+
901
915
}
902
916
return loadOk;
903
917
}
@@ -930,6 +944,14 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
930
944
if (bodyUniqueIdPtr)
931
945
*bodyUniqueIdPtr= bodyUniqueId;
932
946
947
+ // quick prototype of 'save world' for crude world editing
948
+ {
949
+ SaveWorldObjectData sd;
950
+ sd.m_fileName = fileName;
951
+ sd.m_bodyUniqueIds .push_back (bodyUniqueId);
952
+ m_data->m_saveWorldBodyData .push_back (sd);
953
+ }
954
+
933
955
u2b.setBodyUniqueId (bodyUniqueId);
934
956
InternalBodyHandle* bodyHandle = m_data->getHandle (bodyUniqueId);
935
957
@@ -1336,6 +1358,154 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
1336
1358
hasStatus = true ;
1337
1359
break ;
1338
1360
}
1361
+ case CMD_SAVE_WORLD:
1362
+ {
1363
+ // /this is a very rudimentary way to save the state of the world, for scene authoring
1364
+ // /many todo's, for example save the state of motor controllers etc.
1365
+
1366
+ if (clientCmd.m_sdfArguments .m_sdfFileName )
1367
+ {
1368
+ // saveWorld(clientCmd.m_sdfArguments.m_sdfFileName);
1369
+
1370
+ FILE* f = fopen (clientCmd.m_sdfArguments .m_sdfFileName ," w" );
1371
+ if (f)
1372
+ {
1373
+ char line[1024 ];
1374
+ {
1375
+ sprintf (line," import pybullet as p\n " );
1376
+ int len = strlen (line);
1377
+ fwrite (line,len,1 ,f);
1378
+ }
1379
+ {
1380
+ sprintf (line," p.connect(p.SHARED_MEMORY)\n " );
1381
+ int len = strlen (line);
1382
+ fwrite (line,len,1 ,f);
1383
+ }
1384
+ // for each objects ...
1385
+ for (int i=0 ;i<m_data->m_saveWorldBodyData .size ();i++)
1386
+ {
1387
+ SaveWorldObjectData& sd = m_data->m_saveWorldBodyData [i];
1388
+
1389
+ for (int i=0 ;i<sd.m_bodyUniqueIds .size ();i++)
1390
+ {
1391
+ {
1392
+ int bodyUniqueId = sd.m_bodyUniqueIds [i];
1393
+ InteralBodyData* body = m_data->getHandle (bodyUniqueId);
1394
+ if (body)
1395
+ {
1396
+ if (body->m_multiBody )
1397
+ {
1398
+ btMultiBody* mb = body->m_multiBody ;
1399
+
1400
+ btTransform comTr = mb->getBaseWorldTransform ();
1401
+ btTransform tr = comTr * body->m_rootLocalInertialFrame .inverse ();
1402
+
1403
+ if (strstr (sd.m_fileName .c_str ()," .urdf" ))
1404
+ {
1405
+ sprintf (line," objects = [p.loadURDF(\" %s\" , %f,%f,%f,%f,%f,%f,%f)]\n " ,sd.m_fileName .c_str (),
1406
+ tr.getOrigin ()[0 ],tr.getOrigin ()[1 ],tr.getOrigin ()[2 ],
1407
+ tr.getRotation ()[0 ],tr.getRotation ()[1 ],tr.getRotation ()[2 ],tr.getRotation ()[3 ]);
1408
+ int len = strlen (line);
1409
+ fwrite (line,len,1 ,f);
1410
+ }
1411
+
1412
+ if (strstr (sd.m_fileName .c_str ()," .sdf" ) && i==0 )
1413
+ {
1414
+ sprintf (line," objects = p.loadSDF(\" %s\" )\n " ,sd.m_fileName .c_str ());
1415
+ int len = strlen (line);
1416
+ fwrite (line,len,1 ,f);
1417
+ }
1418
+
1419
+ if (strstr (sd.m_fileName .c_str ()," .sdf" ) || ((strstr (sd.m_fileName .c_str ()," .urdf" )) && mb->getNumLinks ()) )
1420
+ {
1421
+ sprintf (line," ob = objects[%d]\n " ,i);
1422
+ int len = strlen (line);
1423
+ fwrite (line,len,1 ,f);
1424
+ }
1425
+
1426
+ if (strstr (sd.m_fileName .c_str ()," .sdf" ))
1427
+ {
1428
+ sprintf (line," p.resetBasePositionAndOrientation(ob,[%f,%f,%f],[%f,%f,%f,%f])\n " ,
1429
+ comTr.getOrigin ()[0 ],comTr.getOrigin ()[1 ],comTr.getOrigin ()[2 ],
1430
+ comTr.getRotation ()[0 ],comTr.getRotation ()[1 ],comTr.getRotation ()[2 ],comTr.getRotation ()[3 ]);
1431
+ int len = strlen (line);
1432
+ fwrite (line,len,1 ,f);
1433
+ }
1434
+
1435
+ if (mb->getNumLinks ())
1436
+ {
1437
+ {
1438
+ sprintf (line," jointPositions=[" );
1439
+ int len = strlen (line);
1440
+ fwrite (line,len,1 ,f);
1441
+ }
1442
+
1443
+ for (int i=0 ;i<mb->getNumLinks ();i++)
1444
+ {
1445
+ btScalar jointPos = mb->getJointPosMultiDof (i)[0 ];
1446
+ if (i<mb->getNumLinks ()-1 )
1447
+ {
1448
+ sprintf (line," %f," ,jointPos);
1449
+ int len = strlen (line);
1450
+ fwrite (line,len,1 ,f);
1451
+ } else
1452
+ {
1453
+ sprintf (line," %f " ,jointPos);
1454
+ int len = strlen (line);
1455
+ fwrite (line,len,1 ,f);
1456
+ }
1457
+ }
1458
+
1459
+ {
1460
+ sprintf (line," ]\n for jointIndex in range (p.getNumJoints(ob)):\n\t p.resetJointState(ob,jointIndex,jointPositions[jointIndex])\n\n " );
1461
+ int len = strlen (line);
1462
+ fwrite (line,len,1 ,f);
1463
+ }
1464
+ }
1465
+ } else
1466
+ {
1467
+ // todo: btRigidBody/btSoftBody etc case
1468
+ }
1469
+ }
1470
+ }
1471
+
1472
+ }
1473
+
1474
+ // for URDF, load at origin, then reposition...
1475
+
1476
+
1477
+ struct SaveWorldObjectData
1478
+ {
1479
+ b3AlignedObjectArray<int > m_bodyUniqueIds;
1480
+ std::string m_fileName;
1481
+ };
1482
+ }
1483
+
1484
+ {
1485
+ btVector3 grav=this ->m_data ->m_dynamicsWorld ->getGravity ();
1486
+ sprintf (line," p.setGravity(%f,%f,%f)\n " ,grav[0 ],grav[1 ],grav[2 ]);
1487
+ int len = strlen (line);
1488
+ fwrite (line,len,1 ,f);
1489
+ }
1490
+
1491
+
1492
+ {
1493
+ sprintf (line," p.stepSimulation()\n p.disconnect()\n " );
1494
+ int len = strlen (line);
1495
+ fwrite (line,len,1 ,f);
1496
+ }
1497
+ fclose (f);
1498
+ }
1499
+
1500
+
1501
+ serverStatusOut.m_type = CMD_SAVE_WORLD_COMPLETED;
1502
+ hasStatus = true ;
1503
+ break ;
1504
+ }
1505
+ serverStatusOut.m_type = CMD_SAVE_WORLD_FAILED;
1506
+ hasStatus = true ;
1507
+ break ;
1508
+ }
1339
1509
case CMD_LOAD_SDF:
1340
1510
{
1341
1511
const SdfArgs& sdfArgs = clientCmd.m_sdfArguments ;
0 commit comments