Allow choosing loaded as btRigidBody with RobotSimAPI.
This commit is contained in:
@@ -55,6 +55,16 @@ b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClie
|
||||
return (b3SharedMemoryCommandHandle) command;
|
||||
}
|
||||
|
||||
int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_LOAD_URDF);
|
||||
command->m_updateFlags |=URDF_ARGS_USE_MULTIBODY;
|
||||
command->m_urdfArguments.m_useMultiBody = useMultiBody;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase)
|
||||
{
|
||||
@@ -67,8 +77,6 @@ int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle,
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
|
||||
@@ -877,6 +877,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
}
|
||||
|
||||
btMultiBody* mb = creation.getBulletMultiBody();
|
||||
|
||||
if (useMultiBody)
|
||||
{
|
||||
|
||||
@@ -944,7 +945,6 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
|
||||
} else
|
||||
{
|
||||
btAssert(0);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user