preliminary work towards saveState/restoreState and saveRestoreState.py example (not implemented yet)

allow multiple options in connect, for example: p.connect(p.GUI, options="--width=640, --height=480")
This commit is contained in:
Erwin Coumans
2017-12-28 10:05:51 -08:00
parent 799d030874
commit 97547eda0d
15 changed files with 552 additions and 143 deletions

View File

@@ -59,6 +59,10 @@ struct btRigidBodyFloatData;
#define btRigidBodyData btRigidBodyFloatData
#endif//BT_USE_DOUBLE_PRECISION
enum btWorldImporterFlags
{
eRESTORE_EXISTING_OBJECTS=1,//don't create new objects
};
class btWorldImporter
{
@@ -66,6 +70,7 @@ protected:
btDynamicsWorld* m_dynamicsWorld;
int m_verboseMode;
int m_importerFlags;
btAlignedObjectArray<btCollisionShape*> m_allocatedCollisionShapes;
btAlignedObjectArray<btCollisionObject*> m_allocatedRigidBodies;
@@ -131,6 +136,18 @@ public:
return m_verboseMode;
}
void setImporterFlags(int importerFlags)
{
m_importerFlags = importerFlags;
}
int getImporterFlags() const
{
return m_importerFlags;
}
// query for data
int getNumCollisionShapes() const;
btCollisionShape* getCollisionShapeByIndex(int index);