Fix some inconsistencies in URDF file handling between btRigidBody and btMultiBody

(rotation order and application of root-inertial-frame offset)
This commit is contained in:
erwin coumans
2016-08-18 09:44:33 -07:00
parent 8a780fa0a4
commit 6005e54aa1
3 changed files with 29 additions and 16 deletions

View File

@@ -239,7 +239,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf");
//setting the initial position, orientation and other arguments are optional
double startPosX = 0;
static double startPosY = 1;
static double startPosY = 0;
double startPosZ = 0;
b3LoadUrdfCommandSetStartPosition(commandHandle, startPosX,startPosY,startPosZ);
startPosY += 2.f;