Split Bullet/src/LinearMath/btSerializer.cpp into btSerializer64.cpp to make it easier to rebuild serialization structure.
Add several MSVC optimization flags to cmake. Bump up VERSION because serialization format changed Expose btScalar& jointMaxForce, btScalar& jointMaxVelocity to 'getJointInfo2' API, add backwards compatibility to examples\Importers\ImportURDFDemo\URDFImporterInterface::getJointInfo. pybullet: expose 4 more fields to getJointInfo: jointLowerLimit/jointUpperLimit/jointMaxForce/jointMaxVelocity fix performance issue in CMD_ACTUAL_STATE_UPDATE_COMPLETED
This commit is contained in:
@@ -360,12 +360,14 @@ void BulletURDFImporter::getMassAndInertia(int linkIndex, btScalar& mass,btVect
|
||||
}
|
||||
}
|
||||
|
||||
bool BulletURDFImporter::getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction) const
|
||||
bool BulletURDFImporter::getJointInfo2(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction, btScalar& jointMaxForce, btScalar& jointMaxVelocity) const
|
||||
{
|
||||
jointLowerLimit = 0.f;
|
||||
jointUpperLimit = 0.f;
|
||||
jointDamping = 0.f;
|
||||
jointFriction = 0.f;
|
||||
jointMaxForce = 0.f;
|
||||
jointMaxVelocity = 0.f;
|
||||
|
||||
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(urdfLinkIndex);
|
||||
btAssert(linkPtr);
|
||||
@@ -384,7 +386,8 @@ bool BulletURDFImporter::getJointInfo(int urdfLinkIndex, btTransform& parent2joi
|
||||
jointUpperLimit = pj->m_upperLimit;
|
||||
jointDamping = pj->m_jointDamping;
|
||||
jointFriction = pj->m_jointFriction;
|
||||
|
||||
jointMaxForce = pj->m_effortLimit;
|
||||
jointMaxVelocity = pj->m_velocityLimit;
|
||||
return true;
|
||||
} else
|
||||
{
|
||||
@@ -394,6 +397,14 @@ bool BulletURDFImporter::getJointInfo(int urdfLinkIndex, btTransform& parent2joi
|
||||
}
|
||||
|
||||
return false;
|
||||
|
||||
};
|
||||
|
||||
bool BulletURDFImporter::getJointInfo(int urdfLinkIndex, btTransform& parent2joint, btTransform& linkTransformInWorld, btVector3& jointAxisInJointSpace, int& jointType, btScalar& jointLowerLimit, btScalar& jointUpperLimit, btScalar& jointDamping, btScalar& jointFriction) const
|
||||
{
|
||||
btScalar jointMaxForce;
|
||||
btScalar jointMaxVelocity;
|
||||
return getJointInfo2(urdfLinkIndex, parent2joint, linkTransformInWorld, jointAxisInJointSpace, jointType, jointLowerLimit, jointUpperLimit, jointDamping, jointFriction,jointMaxForce,jointMaxVelocity);
|
||||
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user