expose b3LoadMJCFCommandSetFlags / pybullet.pybullet_loadMJCF(fileName,flags=pybullet.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)

This commit is contained in:
Erwin Coumans
2017-05-10 15:01:25 -07:00
parent d54eab16e1
commit 53a82819a0
10 changed files with 89 additions and 16 deletions

View File

@@ -160,6 +160,16 @@ b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClie
return 0;
}
void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_LOAD_MJCF);
if (command->m_type == CMD_LOAD_MJCF)
{
command->m_mjcfArguments.m_flags = flags;
command->m_updateFlags |= URDF_ARGS_HAS_CUSTOM_URDF_FLAGS;
}
}
b3SharedMemoryCommandHandle b3LoadBunnyCommandInit(b3PhysicsClientHandle physClient)
{

View File

@@ -237,7 +237,7 @@ int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int fla
b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName);
b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName);
b3SharedMemoryCommandHandle b3LoadMJCFCommandInit(b3PhysicsClientHandle physClient, const char* fileName);
void b3LoadMJCFCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
///compute the forces to achieve an acceleration, given a state q and qdot using inverse dynamics

View File

@@ -5693,7 +5693,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
b3Printf("Processed CMD_LOAD_MJCF:%s", mjcfArgs.m_mjcfFileName);
}
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (mjcfArgs.m_useMultiBody!=0) : true;
int flags = CUF_USE_MJCF;//CUF_USE_URDF_INERTIA
int flags = CUF_USE_MJCF;
if (clientCmd.m_updateFlags&URDF_ARGS_HAS_CUSTOM_URDF_FLAGS)
{
flags |= clientCmd.m_mjcfArguments.m_flags;
}
bool completedOk = loadMjcf(mjcfArgs.m_mjcfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody, flags);
if (completedOk)
{

View File

@@ -93,10 +93,13 @@ struct UrdfArgs
int m_urdfFlags;
};
struct MjcfArgs
{
char m_mjcfFileName[MAX_URDF_FILENAME_LENGTH];
int m_useMultiBody;
int m_flags;
};
struct BulletDataStreamArgs

View File

@@ -509,6 +509,8 @@ enum eURDF_Flags
{
URDF_USE_INERTIA_FROM_FILE=2,//sync with URDF2Bullet.h 'ConvertURDFFlags'
URDF_USE_SELF_COLLISION=8,//see CUF_USE_SELF_COLLISION
URDF_USE_SELF_COLLISION_EXCLUDE_PARENT=16,
URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS=32,
};
#endif//SHARED_MEMORY_PUBLIC_H