Preliminary version of pybullet.createMultiBody including links connected to parent by a joint.

See createMultiBodyLinks.py example.
This commit is contained in:
Erwin Coumans
2017-06-19 13:15:05 -07:00
parent f3c11b6f31
commit 7441515c0e
6 changed files with 181 additions and 25 deletions

View File

@@ -993,6 +993,12 @@ int b3CreateMultiBodyBase(b3SharedMemoryCommandHandle commandHandle, double mass
command->m_createMultiBodyArgs.m_linkVisualShapeUniqueIds[baseLinkIndex] = visualShapeUniqueId;
command->m_createMultiBodyArgs.m_linkMasses[baseLinkIndex] = mass;
command->m_createMultiBodyArgs.m_linkParentIndices[baseLinkIndex] = -2;//no parent
command->m_createMultiBodyArgs.m_linkJointAxis[baseLinkIndex+0]=0;
command->m_createMultiBodyArgs.m_linkJointAxis[baseLinkIndex+1]=0;
command->m_createMultiBodyArgs.m_linkJointAxis[baseLinkIndex+2]=0;
command->m_createMultiBodyArgs.m_linkJointTypes[baseLinkIndex]=-1;
command->m_createMultiBodyArgs.m_numLinks++;
}
return numLinks;
@@ -1004,6 +1010,8 @@ int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double link
double linkVisualShapeIndex,
double linkPosition[3],
double linkOrientation[4],
double linkInertialFramePosition[3],
double linkInertialFrameOrientation[4],
int linkParentIndex,
int linkJointType,
double linkJointAxis[3])
@@ -1033,23 +1041,23 @@ int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double link
command->m_createMultiBodyArgs.m_linkInertias[linkIndex*3+2] = linkMass;
command->m_createMultiBodyArgs.m_linkInertialFramePositions[linkIndex*3+0] = 0;
command->m_createMultiBodyArgs.m_linkInertialFramePositions[linkIndex*3+1] = 0;
command->m_createMultiBodyArgs.m_linkInertialFramePositions[linkIndex*3+2] = 0;
command->m_createMultiBodyArgs.m_linkInertialFramePositions[linkIndex*3+0] = linkInertialFramePosition[0];
command->m_createMultiBodyArgs.m_linkInertialFramePositions[linkIndex*3+1] = linkInertialFramePosition[1];
command->m_createMultiBodyArgs.m_linkInertialFramePositions[linkIndex*3+2] = linkInertialFramePosition[2];
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+0] = 0;
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+1] = 0;
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+2] = 0;
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+3] = 1;
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+0] = linkInertialFrameOrientation[0];
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+1] = linkInertialFrameOrientation[1];
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+2] = linkInertialFrameOrientation[2];
command->m_createMultiBodyArgs.m_linkInertialFrameOrientations[linkIndex*4+3] = linkInertialFrameOrientation[3];
command->m_createMultiBodyArgs.m_linkCollisionShapeUniqueIds[linkIndex]= linkCollisionShapeIndex;
command->m_createMultiBodyArgs.m_linkVisualShapeUniqueIds[linkIndex] = linkVisualShapeIndex;
command->m_createMultiBodyArgs.m_linkParentIndices[linkIndex] = linkParentIndex;
command->m_createMultiBodyArgs.m_linkJointTypes[linkIndex] = linkJointType;
command->m_createMultiBodyArgs.m_linkJointAxis[0] = linkJointAxis[0];
command->m_createMultiBodyArgs.m_linkJointAxis[1] = linkJointAxis[1];
command->m_createMultiBodyArgs.m_linkJointAxis[2] = linkJointAxis[2];
command->m_createMultiBodyArgs.m_linkJointAxis[3*linkIndex+0] = linkJointAxis[0];
command->m_createMultiBodyArgs.m_linkJointAxis[3*linkIndex+1] = linkJointAxis[1];
command->m_createMultiBodyArgs.m_linkJointAxis[3*linkIndex+2] = linkJointAxis[2];
command->m_createMultiBodyArgs.m_linkMasses[linkIndex] = linkMass;
command->m_createMultiBodyArgs.m_numLinks++;

View File

@@ -348,6 +348,8 @@ int b3CreateMultiBodyLink(b3SharedMemoryCommandHandle commandHandle, double link
double linkVisualShapeIndex,
double linkPosition[3],
double linkOrientation[4],
double linkInertialFramePosition[3],
double linkInertialFrameOrientation[4],
int linkParentIndex,
int linkJointType,
double linkJointAxis[3]);

View File

@@ -1547,7 +1547,11 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
virtual std::string getLinkName(int linkIndex) const
{
return "link";
std::string linkName = "link";
char numstr[21]; // enough to hold all numbers up to 64-bits
sprintf(numstr, "%d", linkIndex);
linkName = linkName + numstr;
return linkName;
}
//various derived class in internal source code break with new pure virtual methods, so provide some default implementation
@@ -1587,8 +1591,11 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
virtual std::string getJointName(int linkIndex) const
{
b3Assert(0);
return "joint";
std::string jointName = "joint";
char numstr[21]; // enough to hold all numbers up to 64-bits
sprintf(numstr, "%d", linkIndex);
jointName = jointName + numstr;
return jointName;
}
//fill mass and inertial data. If inertial data is missing, please initialize mass, inertia to sensitive values, and inertialFrame to identity.
@@ -1623,7 +1630,7 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
{
for (int i=0;i<m_createBodyArgs.m_numLinks;i++)
{
if (m_createBodyArgs.m_linkParents[i] == urdfLinkIndex)
if (m_createBodyArgs.m_linkParentIndices[i] == urdfLinkIndex)
{
childLinkIndices.push_back(i);
}
@@ -1638,10 +1645,72 @@ struct ProgrammaticUrdfInterface : public URDFImporterInterface
virtual bool getJointInfo2(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity) const
{
//backwards compatibility for custom file importers
jointMaxForce = 0;
jointMaxVelocity = 0;
return getJointInfo(urdfLinkIndex, parent2joint, linkTransformInWorld, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction);
bool isValid = false;
int jointTypeOrg = m_createBodyArgs.m_linkJointTypes[urdfLinkIndex];
switch (jointTypeOrg)
{
case eRevoluteType:
{
isValid = true;
jointType = URDFRevoluteJoint;
break;
}
case ePrismaticType:
{
isValid = true;
jointType = URDFPrismaticJoint;
break;
}
case eFixedType:
{
isValid = true;
jointType = URDFFixedJoint;
break;
}
//case eSphericalType:
//case ePlanarType:
//case eFixedType:
//case ePoint2PointType:
//case eGearType:
default:
{
}
};
if (isValid)
{
//backwards compatibility for custom file importers
jointMaxForce = 0;
jointMaxVelocity = 0;
jointFriction = 0;
jointDamping = 0;
jointLowerLimit = 1;
jointUpperLimit = -1;
parent2joint.setOrigin(btVector3(
m_createBodyArgs.m_linkPositions[urdfLinkIndex*3+0],
m_createBodyArgs.m_linkPositions[urdfLinkIndex*3+1],
m_createBodyArgs.m_linkPositions[urdfLinkIndex*3+2]));
parent2joint.setRotation(btQuaternion(
m_createBodyArgs.m_linkOrientations[urdfLinkIndex*4+0],
m_createBodyArgs.m_linkOrientations[urdfLinkIndex*4+1],
m_createBodyArgs.m_linkOrientations[urdfLinkIndex*4+2],
m_createBodyArgs.m_linkOrientations[urdfLinkIndex*4+3]
));
linkTransformInWorld.setIdentity();
jointAxisInJointSpace.setValue(
m_createBodyArgs.m_linkJointAxis[3*urdfLinkIndex+0],
m_createBodyArgs.m_linkJointAxis[3*urdfLinkIndex+1],
m_createBodyArgs.m_linkJointAxis[3*urdfLinkIndex+2]);
}
return isValid;
};
virtual bool getRootTransformInWorld(btTransform& rootTransformInWorld) const

View File

@@ -854,7 +854,6 @@ struct b3CreateMultiBodyArgs
double m_linkOrientations[4*MAX_CREATE_MULTI_BODY_LINKS];
int m_numLinks;
int m_linkParents[MAX_CREATE_MULTI_BODY_LINKS];
double m_linkMasses[MAX_CREATE_MULTI_BODY_LINKS];
double m_linkInertias[MAX_CREATE_MULTI_BODY_LINKS*3];