Expose 'flags' option for loadURDF, to allow customization of the URDF loading process while maintaining backward compatibility.

For example: URDF_USE_INERTIA_FROM_FILE flag. By default, URDF2Bullet will re-compute the inertia tensor based on mass and volume, because most URDF files have bogus Inertia values.
This commit is contained in:
Erwin Coumans
2017-03-27 08:30:20 -07:00
parent d78909aef9
commit 4911916937
9 changed files with 44 additions and 13 deletions

View File

@@ -238,6 +238,19 @@ int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle,
return -1;
}
int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_LOAD_URDF);
if (command && (command->m_type == CMD_LOAD_URDF))
{
command->m_updateFlags |= URDF_ARGS_HAS_CUSTOM_URDF_FLAGS;
command->m_urdfArguments.m_urdfFlags = flags;
}
return 0;
}
int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -217,6 +217,7 @@ int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle,
int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW);
int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody);
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase);
int b3LoadUrdfCommandSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
b3SharedMemoryCommandHandle b3LoadBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName);
b3SharedMemoryCommandHandle b3SaveBulletCommandInit(b3PhysicsClientHandle physClient, const char* fileName);

View File

@@ -1539,7 +1539,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe
bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn,
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes)
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags)
{
BT_PROFILE("loadURDF");
btAssert(m_data->m_dynamicsWorld);
@@ -1597,7 +1597,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
// printf("urdf root link index = %d\n",rootLinkIndex);
MyMultiBodyCreator creation(m_data->m_guiHelper);
ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix());
ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),flags);
for (int i=0;i<u2b.getNumAllocatedCollisionShapes();i++)
{
@@ -2617,6 +2617,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
initialPos[1] = urdfArgs.m_initialPosition[1];
initialPos[2] = urdfArgs.m_initialPosition[2];
}
int urdfFlags = 0;
if (clientCmd.m_updateFlags & URDF_ARGS_HAS_CUSTOM_URDF_FLAGS)
{
urdfFlags = urdfArgs.m_urdfFlags;
}
if (clientCmd.m_updateFlags & URDF_ARGS_INITIAL_ORIENTATION)
{
initialOrn[0] = urdfArgs.m_initialOrientation[0];
@@ -2630,8 +2635,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
//load the actual URDF and send a report: completed or failed
bool completedOk = loadUrdf(urdfArgs.m_urdfFileName,
initialPos,initialOrn,
useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes);
useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes, urdfFlags);
if (completedOk)
{
@@ -5399,7 +5403,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets()
btVector3 spawnDir = mat.getColumn(0);
btVector3 shiftPos = spawnDir*spawnDistance;
btVector3 spawnPos = gVRGripperPos + shiftPos;
loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size(),0);
//loadUrdf("lego/lego.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
m_data->m_sphereId = bodyId;
InteralBodyData* parentBody = m_data->getHandle(bodyId);

View File

@@ -35,7 +35,7 @@ protected:
bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags);
bool loadUrdf(const char* fileName, const class btVector3& pos, const class btQuaternion& orn,
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes);
bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes, int flags=0);
bool loadMjcf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes, bool useMultiBody, int flags);

View File

@@ -79,6 +79,7 @@ enum EnumUrdfArgsUpdateFlags
URDF_ARGS_INITIAL_ORIENTATION=4,
URDF_ARGS_USE_MULTIBODY=8,
URDF_ARGS_USE_FIXED_BASE=16,
URDF_ARGS_HAS_CUSTOM_URDF_FLAGS = 32
};
@@ -89,6 +90,7 @@ struct UrdfArgs
double m_initialOrientation[4];
int m_useMultiBody;
int m_useFixedBase;
int m_urdfFlags;
};
struct MjcfArgs

View File

@@ -447,4 +447,9 @@ enum eCONNECT_METHOD {
eCONNECT_TCP = 5,
};
enum eURDF_Flags
{
URDF_USE_INERTIA_FROM_FILE=2,//sync with URDF2Bullet.h 'ConvertURDFFlags'
};
#endif//SHARED_MEMORY_PUBLIC_H