add capsule support in urdf parser (non-standard extension), capsule.urdf
fix btCapsuleShape (X,Y,Z) margin issue fix uninitialized variables in TinyRenderer: m_hasLightDistance, m_hasLightAmbientCoeff, m_hasLightDiffuseCoeff, m_hasLightSpecularCoeff pybullet/shared memory API 'getClosestPoints' / b3InitClosestDistanceQuery, only report contacts equal/smaller distance than given
This commit is contained in:
@@ -455,6 +455,16 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co
|
||||
|
||||
switch (collision->m_geometry.m_type)
|
||||
{
|
||||
case URDF_GEOM_CAPSULE:
|
||||
{
|
||||
btScalar radius = collision->m_geometry.m_capsuleRadius;
|
||||
btScalar height = btScalar(2.f)*collision->m_geometry.m_capsuleHalfHeight;
|
||||
btCapsuleShapeZ* capsuleShape = new btCapsuleShapeZ(radius,height);
|
||||
shape = capsuleShape;
|
||||
shape ->setMargin(gUrdfDefaultCollisionMargin);
|
||||
break;
|
||||
}
|
||||
|
||||
case URDF_GEOM_CYLINDER:
|
||||
{
|
||||
btScalar cylRadius = collision->m_geometry.m_cylinderRadius;
|
||||
|
||||
@@ -380,7 +380,20 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger*
|
||||
geom.m_cylinderLength = urdfLexicalCast<double>(shape->Attribute("length"));
|
||||
|
||||
}
|
||||
|
||||
else if (type_name == "capsule")
|
||||
{
|
||||
geom.m_type = URDF_GEOM_CAPSULE;
|
||||
if (!shape->Attribute("length") ||
|
||||
!shape->Attribute("radius"))
|
||||
{
|
||||
logger->reportError("Capsule shape must have both length and radius attributes");
|
||||
return false;
|
||||
}
|
||||
geom.m_hasFromTo = false;
|
||||
geom.m_capsuleRadius = urdfLexicalCast<double>(shape->Attribute("radius"));
|
||||
geom.m_capsuleHalfHeight = btScalar(0.5)*urdfLexicalCast<double>(shape->Attribute("length"));
|
||||
|
||||
}
|
||||
else if (type_name == "mesh")
|
||||
{
|
||||
geom.m_type = URDF_GEOM_MESH;
|
||||
|
||||
@@ -3358,25 +3358,28 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
virtual btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap, int partId0, int index0, const btCollisionObjectWrapper* colObj1Wrap, int partId1, int index1)
|
||||
{
|
||||
b3ContactPointData pt;
|
||||
pt.m_bodyUniqueIdA = m_bodyUniqueIdA;
|
||||
pt.m_bodyUniqueIdB = m_bodyUniqueIdB;
|
||||
const btManifoldPoint& srcPt = cp;
|
||||
pt.m_contactDistance = srcPt.getDistance();
|
||||
pt.m_contactFlags = 0;
|
||||
pt.m_linkIndexA = m_linkIndexA;
|
||||
pt.m_linkIndexB = m_linkIndexB;
|
||||
for (int j = 0; j < 3; j++)
|
||||
if (cp.m_distance1<=m_closestDistanceThreshold)
|
||||
{
|
||||
pt.m_contactNormalOnBInWS[j] = srcPt.m_normalWorldOnB[j];
|
||||
pt.m_positionOnAInWS[j] = srcPt.getPositionWorldOnA()[j];
|
||||
pt.m_positionOnBInWS[j] = srcPt.getPositionWorldOnB()[j];
|
||||
b3ContactPointData pt;
|
||||
pt.m_bodyUniqueIdA = m_bodyUniqueIdA;
|
||||
pt.m_bodyUniqueIdB = m_bodyUniqueIdB;
|
||||
const btManifoldPoint& srcPt = cp;
|
||||
pt.m_contactDistance = srcPt.getDistance();
|
||||
pt.m_contactFlags = 0;
|
||||
pt.m_linkIndexA = m_linkIndexA;
|
||||
pt.m_linkIndexB = m_linkIndexB;
|
||||
for (int j = 0; j < 3; j++)
|
||||
{
|
||||
pt.m_contactNormalOnBInWS[j] = srcPt.m_normalWorldOnB[j];
|
||||
pt.m_positionOnAInWS[j] = srcPt.getPositionWorldOnA()[j];
|
||||
pt.m_positionOnBInWS[j] = srcPt.getPositionWorldOnB()[j];
|
||||
}
|
||||
pt.m_normalForce = srcPt.getAppliedImpulse() / m_deltaTime;
|
||||
// pt.m_linearFrictionForce = srcPt.m_appliedImpulseLateral1;
|
||||
m_cachedContactPoints.push_back(pt);
|
||||
}
|
||||
pt.m_normalForce = srcPt.getAppliedImpulse() / m_deltaTime;
|
||||
// pt.m_linearFrictionForce = srcPt.m_appliedImpulseLateral1;
|
||||
m_cachedContactPoints.push_back(pt);
|
||||
|
||||
return 1;
|
||||
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
@@ -94,9 +94,19 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
m_swWidth(START_WIDTH),
|
||||
m_swHeight(START_HEIGHT),
|
||||
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB),
|
||||
m_lightDirection(btVector3(-5,200,-40)),
|
||||
m_hasLightDirection(false),
|
||||
m_lightColor(btVector3(1.0,1.0,1.0)),
|
||||
m_hasLightColor(false),
|
||||
m_hasShadow(false)
|
||||
m_lightDistance(2.0),
|
||||
m_hasLightDistance(false),
|
||||
m_lightAmbientCoeff(0.6),
|
||||
m_hasLightAmbientCoeff(false),
|
||||
m_lightDiffuseCoeff(0.35),
|
||||
m_hasLightDiffuseCoeff(false),
|
||||
m_lightSpecularCoeff(0.05),
|
||||
m_hasLightSpecularCoeff(false),
|
||||
m_hasShadow(false)
|
||||
{
|
||||
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
||||
m_shadowBuffer.resize(m_swWidth*m_swHeight);
|
||||
|
||||
Reference in New Issue
Block a user