mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
Allow choosing loaded as btRigidBody with RobotSimAPI.
This commit is contained in:
parent
9c4cfde3d6
commit
4bc31394a0
35
data/cube_small.sdf
Normal file
35
data/cube_small.sdf
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
<sdf version='1.6'>
|
||||||
|
<world name='default'>
|
||||||
|
<model name='unit_box_0'>
|
||||||
|
<pose frame=''>0 0 0.107 0 0 0</pose>
|
||||||
|
<link name='unit_box_0::link'>
|
||||||
|
<inertial>
|
||||||
|
<mass>0.1</mass>
|
||||||
|
<inertia>
|
||||||
|
<ixx>1.0</ixx>
|
||||||
|
<ixy>0</ixy>
|
||||||
|
<ixz>0</ixz>
|
||||||
|
<iyy>1.0</iyy>
|
||||||
|
<iyz>0</iyz>
|
||||||
|
<izz>1.0</izz>
|
||||||
|
</inertia>
|
||||||
|
</inertial>
|
||||||
|
<collision name='collision'>
|
||||||
|
<geometry>
|
||||||
|
<box>
|
||||||
|
<size>0.05 0.05 0.05</size>
|
||||||
|
</box>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
<visual name='visual'>
|
||||||
|
<geometry>
|
||||||
|
<mesh>
|
||||||
|
<scale>0.05 0.05 0.05</scale>
|
||||||
|
<uri>cube.obj</uri>
|
||||||
|
</mesh>
|
||||||
|
</geometry>
|
||||||
|
</visual>
|
||||||
|
</link>
|
||||||
|
</model>
|
||||||
|
</world>
|
||||||
|
</sdf>
|
@ -82,7 +82,6 @@ public:
|
|||||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
{
|
{
|
||||||
b3RobotSimLoadFileArgs args("");
|
b3RobotSimLoadFileArgs args("");
|
||||||
args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
|
args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
|
||||||
@ -132,9 +131,11 @@ public:
|
|||||||
{
|
{
|
||||||
b3RobotSimLoadFileArgs args("");
|
b3RobotSimLoadFileArgs args("");
|
||||||
b3RobotSimLoadFileResults results;
|
b3RobotSimLoadFileResults results;
|
||||||
args.m_fileName = "cube_small.urdf";
|
args.m_fileName = "cube_small.sdf";
|
||||||
args.m_startPosition.setValue(0,0,.107);
|
args.m_startPosition.setValue(0,0,.107);
|
||||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||||
|
args.m_useMultiBody = false;
|
||||||
|
args.m_fileType = 2;
|
||||||
m_robotSim.loadFile(args,results);
|
m_robotSim.loadFile(args,results);
|
||||||
}
|
}
|
||||||
if (1)
|
if (1)
|
||||||
@ -144,6 +145,7 @@ public:
|
|||||||
args.m_startPosition.setValue(0,0,0);
|
args.m_startPosition.setValue(0,0,0);
|
||||||
args.m_startOrientation.setEulerZYX(0,0,0);
|
args.m_startOrientation.setEulerZYX(0,0,0);
|
||||||
args.m_forceOverrideFixedBase = true;
|
args.m_forceOverrideFixedBase = true;
|
||||||
|
args.m_useMultiBody = true;
|
||||||
b3RobotSimLoadFileResults results;
|
b3RobotSimLoadFileResults results;
|
||||||
m_robotSim.loadFile(args,results);
|
m_robotSim.loadFile(args,results);
|
||||||
|
|
||||||
|
@ -211,7 +211,10 @@ public:
|
|||||||
return m_cs;
|
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;
|
btCollisionObject* m_obj;
|
||||||
btVector3 m_color2;
|
btVector3 m_color2;
|
||||||
@ -685,6 +688,7 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
|
|||||||
{
|
{
|
||||||
b3LoadUrdfCommandSetUseFixedBase(command,true);
|
b3LoadUrdfCommandSetUseFixedBase(command,true);
|
||||||
}
|
}
|
||||||
|
b3LoadUrdfCommandSetUseMultiBody(command, args.m_useMultiBody);
|
||||||
statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command);
|
statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command);
|
||||||
statusType = b3GetStatusType(statusHandle);
|
statusType = b3GetStatusType(statusHandle);
|
||||||
|
|
||||||
|
@ -23,6 +23,7 @@ struct b3RobotSimLoadFileArgs
|
|||||||
b3Vector3 m_startPosition;
|
b3Vector3 m_startPosition;
|
||||||
b3Quaternion m_startOrientation;
|
b3Quaternion m_startOrientation;
|
||||||
bool m_forceOverrideFixedBase;
|
bool m_forceOverrideFixedBase;
|
||||||
|
bool m_useMultiBody;
|
||||||
int m_fileType;
|
int m_fileType;
|
||||||
|
|
||||||
|
|
||||||
|
@ -55,6 +55,16 @@ b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClie
|
|||||||
return (b3SharedMemoryCommandHandle) command;
|
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)
|
int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase)
|
||||||
{
|
{
|
||||||
@ -67,8 +77,6 @@ int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle,
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
|
int b3LoadUrdfCommandSetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ)
|
||||||
{
|
{
|
||||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
@ -877,6 +877,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
|||||||
}
|
}
|
||||||
|
|
||||||
btMultiBody* mb = creation.getBulletMultiBody();
|
btMultiBody* mb = creation.getBulletMultiBody();
|
||||||
|
|
||||||
if (useMultiBody)
|
if (useMultiBody)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -944,7 +945,6 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
|||||||
|
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
btAssert(0);
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user