export contact friction/damping through URDF and API
convert from contact friction/damping to cfm/erp btCollisionObject::setContactFrictionAndDamping
This commit is contained in:
@@ -418,7 +418,10 @@ void ConvertURDF2BulletInternal(
|
||||
{
|
||||
col->setRollingFriction(contactInfo.m_rollingFriction);
|
||||
}
|
||||
|
||||
if ((contactInfo.m_flags & URDF_CONTACT_HAS_STIFFNESS_DAMPING)!=0)
|
||||
{
|
||||
col->setContactStiffnessAndDamping(contactInfo.m_contactStiffness,contactInfo.m_contactDamping);
|
||||
}
|
||||
|
||||
if (mbLinkIndex>=0) //???? double-check +/- 1
|
||||
{
|
||||
|
||||
@@ -19,7 +19,8 @@ enum URDF_LinkContactFlags
|
||||
URDF_CONTACT_HAS_ROLLING_FRICTION=2,
|
||||
URDF_CONTACT_HAS_INERTIA_SCALING=2,
|
||||
URDF_CONTACT_HAS_CONTACT_CFM=4,
|
||||
URDF_CONTACT_HAS_CONTACT_ERP=8
|
||||
URDF_CONTACT_HAS_CONTACT_ERP=8,
|
||||
URDF_CONTACT_HAS_STIFFNESS_DAMPING=16,
|
||||
};
|
||||
|
||||
struct URDFLinkContactInfo
|
||||
@@ -29,6 +30,9 @@ struct URDFLinkContactInfo
|
||||
btScalar m_inertiaScaling;
|
||||
btScalar m_contactCfm;
|
||||
btScalar m_contactErp;
|
||||
btScalar m_contactStiffness;
|
||||
btScalar m_contactDamping;
|
||||
|
||||
int m_flags;
|
||||
|
||||
URDFLinkContactInfo()
|
||||
@@ -36,7 +40,9 @@ struct URDFLinkContactInfo
|
||||
m_rollingFriction(0),
|
||||
m_inertiaScaling(1),
|
||||
m_contactCfm(0),
|
||||
m_contactErp(0)
|
||||
m_contactErp(0),
|
||||
m_contactStiffness(1e4),
|
||||
m_contactDamping(1)
|
||||
{
|
||||
m_flags = URDF_CONTACT_HAS_LATERAL_FRICTION;
|
||||
}
|
||||
|
||||
@@ -647,26 +647,75 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi
|
||||
}
|
||||
}
|
||||
|
||||
TiXmlElement *rolling_xml = ci->FirstChildElement("rolling_friction");
|
||||
if (rolling_xml)
|
||||
{
|
||||
if (m_parseSDF)
|
||||
TiXmlElement *rolling_xml = ci->FirstChildElement("rolling_friction");
|
||||
if (rolling_xml)
|
||||
{
|
||||
link.m_contactInfo.m_rollingFriction = urdfLexicalCast<double>(rolling_xml->GetText());
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_ROLLING_FRICTION;
|
||||
} else
|
||||
{
|
||||
if (!rolling_xml->Attribute("value"))
|
||||
if (m_parseSDF)
|
||||
{
|
||||
logger->reportError("Link/contact: rolling friction element must have value attribute");
|
||||
return false;
|
||||
link.m_contactInfo.m_rollingFriction = urdfLexicalCast<double>(rolling_xml->GetText());
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_ROLLING_FRICTION;
|
||||
} else
|
||||
{
|
||||
if (!rolling_xml->Attribute("value"))
|
||||
{
|
||||
logger->reportError("Link/contact: rolling friction element must have value attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
link.m_contactInfo.m_rollingFriction = urdfLexicalCast<double>(rolling_xml->Attribute("value"));
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_ROLLING_FRICTION;
|
||||
|
||||
}
|
||||
|
||||
link.m_contactInfo.m_rollingFriction = urdfLexicalCast<double>(rolling_xml->Attribute("value"));
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_ROLLING_FRICTION;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
|
||||
TiXmlElement *stiffness_xml = ci->FirstChildElement("stiffness");
|
||||
if (stiffness_xml)
|
||||
{
|
||||
if (m_parseSDF)
|
||||
{
|
||||
link.m_contactInfo.m_contactStiffness = urdfLexicalCast<double>(stiffness_xml->GetText());
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_STIFFNESS_DAMPING;
|
||||
} else
|
||||
{
|
||||
if (!stiffness_xml->Attribute("value"))
|
||||
{
|
||||
logger->reportError("Link/contact: stiffness element must have value attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
link.m_contactInfo.m_contactStiffness = urdfLexicalCast<double>(stiffness_xml->Attribute("value"));
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_STIFFNESS_DAMPING;
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
{
|
||||
|
||||
TiXmlElement *damping_xml = ci->FirstChildElement("damping");
|
||||
if (damping_xml)
|
||||
{
|
||||
if (m_parseSDF)
|
||||
{
|
||||
link.m_contactInfo.m_contactDamping = urdfLexicalCast<double>(damping_xml->GetText());
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_STIFFNESS_DAMPING;
|
||||
} else
|
||||
{
|
||||
if (!damping_xml->Attribute("value"))
|
||||
{
|
||||
logger->reportError("Link/contact: damping element must have value attribute");
|
||||
return false;
|
||||
}
|
||||
|
||||
link.m_contactInfo.m_contactDamping = urdfLexicalCast<double>(damping_xml->Attribute("value"));
|
||||
link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_STIFFNESS_DAMPING;
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -36,7 +36,6 @@ public:
|
||||
|
||||
};
|
||||
|
||||
extern ContactAddedCallback gContactAddedCallback;
|
||||
|
||||
|
||||
MultiBodySoftContact::MultiBodySoftContact(struct GUIHelperInterface* helper)
|
||||
@@ -47,18 +46,7 @@ m_once(true)
|
||||
|
||||
MultiBodySoftContact::~MultiBodySoftContact()
|
||||
{
|
||||
gContactAddedCallback = 0;
|
||||
}
|
||||
|
||||
|
||||
static bool btMultiBodySoftContactCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
||||
{
|
||||
cp.m_contactCFM = 0.3;
|
||||
cp.m_contactERP = 0.2;
|
||||
cp.m_contactPointFlags |= BT_CONTACT_FLAG_HAS_CONTACT_CFM;
|
||||
cp.m_contactPointFlags |= BT_CONTACT_FLAG_HAS_CONTACT_ERP;
|
||||
return true;
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -66,7 +54,7 @@ static bool btMultiBodySoftContactCallback(btManifoldPoint& cp, const btCollisio
|
||||
|
||||
void MultiBodySoftContact::initPhysics()
|
||||
{
|
||||
gContactAddedCallback = btMultiBodySoftContactCallback;
|
||||
|
||||
int upAxis = 2;
|
||||
|
||||
m_guiHelper->setUpAxis(upAxis);
|
||||
@@ -109,12 +97,13 @@ void MultiBodySoftContact::initPhysics()
|
||||
start.setOrigin(groundOrigin);
|
||||
// start.setRotation(groundOrn);
|
||||
btRigidBody* body = createRigidBody(0,start,box);
|
||||
|
||||
//setContactStiffnessAndDamping will enable compliant rigid body contact
|
||||
body->setContactStiffnessAndDamping(300,10);
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
m_guiHelper->createRigidBodyGraphicsObject(body,color);
|
||||
int flags = body->getCollisionFlags();
|
||||
body->setCollisionFlags(flags|btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -29,7 +29,7 @@ subject to the following restrictions:
|
||||
#include "BulletDynamics/MLCPSolvers/btMLCPSolver.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
|
||||
|
||||
extern ContactAddedCallback gContactAddedCallback;
|
||||
|
||||
|
||||
|
||||
struct RigidBodySoftContact : public CommonRigidBodyBase
|
||||
@@ -40,7 +40,7 @@ struct RigidBodySoftContact : public CommonRigidBodyBase
|
||||
}
|
||||
virtual ~RigidBodySoftContact()
|
||||
{
|
||||
gContactAddedCallback = 0;
|
||||
|
||||
}
|
||||
virtual void initPhysics();
|
||||
virtual void renderScene();
|
||||
@@ -55,21 +55,12 @@ struct RigidBodySoftContact : public CommonRigidBodyBase
|
||||
};
|
||||
|
||||
|
||||
static bool btRigidBodySoftContactCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
|
||||
{
|
||||
cp.m_contactCFM = 0.3;
|
||||
cp.m_contactERP = 0.2;
|
||||
cp.m_contactPointFlags |= BT_CONTACT_FLAG_HAS_CONTACT_CFM;
|
||||
cp.m_contactPointFlags |= BT_CONTACT_FLAG_HAS_CONTACT_ERP;
|
||||
return true;
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void RigidBodySoftContact::initPhysics()
|
||||
{
|
||||
gContactAddedCallback = btRigidBodySoftContactCallback;
|
||||
|
||||
|
||||
m_guiHelper->setUpAxis(1);
|
||||
|
||||
@@ -120,8 +111,9 @@ void RigidBodySoftContact::initPhysics()
|
||||
{
|
||||
btScalar mass(0.);
|
||||
btRigidBody* body = createRigidBody(mass,groundTransform,groundShape, btVector4(0,0,1,1));
|
||||
int flags = body->getCollisionFlags();
|
||||
body->setCollisionFlags(flags|btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
|
||||
|
||||
body->setContactStiffnessAndDamping(300,10);
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -153,7 +153,7 @@ public:
|
||||
|
||||
}
|
||||
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
|
||||
//m_robotSim.setNumSimulationSubSteps(4);
|
||||
m_robotSim.setNumSimulationSubSteps(4);
|
||||
}
|
||||
|
||||
if ((m_options & eTWO_POINT_GRASP)!=0)
|
||||
|
||||
@@ -117,7 +117,7 @@ public:
|
||||
b3RobotSimLoadFileArgs args("");
|
||||
b3RobotSimLoadFileResults results;
|
||||
{
|
||||
args.m_fileName = "cube.urdf";
|
||||
args.m_fileName = "cube_soft.urdf";
|
||||
args.m_startPosition.setValue(0,0,2.5);
|
||||
args.m_startOrientation.setEulerZYX(0,0.2,0);
|
||||
m_robotSim.loadFile(args,results);
|
||||
|
||||
Reference in New Issue
Block a user