Allow choosing loaded as btRigidBody with RobotSimAPI.

This commit is contained in:
yunfeibai
2016-08-16 16:57:48 -07:00
parent 9c4cfde3d6
commit 4bc31394a0
6 changed files with 56 additions and 6 deletions

View File

@@ -82,7 +82,6 @@ public:
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
@@ -132,9 +131,11 @@ public:
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "cube_small.urdf";
args.m_fileName = "cube_small.sdf";
args.m_startPosition.setValue(0,0,.107);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_useMultiBody = false;
args.m_fileType = 2;
m_robotSim.loadFile(args,results);
}
if (1)
@@ -144,6 +145,7 @@ public:
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);

View File

@@ -211,7 +211,10 @@ public:
return m_cs;
}
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color){}
virtual void createRigidBodyGraphicsObject(btRigidBody* body,const btVector3& color)
{
createCollisionObjectGraphicsObject((btCollisionObject*)body, color);
}
btCollisionObject* m_obj;
btVector3 m_color2;
@@ -685,6 +688,7 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
{
b3LoadUrdfCommandSetUseFixedBase(command,true);
}
b3LoadUrdfCommandSetUseMultiBody(command, args.m_useMultiBody);
statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command);
statusType = b3GetStatusType(statusHandle);

View File

@@ -23,6 +23,7 @@ struct b3RobotSimLoadFileArgs
b3Vector3 m_startPosition;
b3Quaternion m_startOrientation;
bool m_forceOverrideFixedBase;
bool m_useMultiBody;
int m_fileType;

View File

@@ -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;

View File

@@ -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;
}