remove that odd triangle in the origin of samurai castle (VR)

add rolling/spinning friction to cube, remove it from plane/samurai.urdf
URDF2Bullet: support joint limits for revolute and prismatic, only if defined (if upper < lower, disable limit)
add some profiling markers to improve performance
This commit is contained in:
erwin coumans
2016-09-19 07:02:43 -07:00
parent 48d42c7c6e
commit db3122233f
23 changed files with 297 additions and 113 deletions

View File

@@ -816,7 +816,7 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi
bool UrdfParser::parseJointLimits(UrdfJoint& joint, TiXmlElement* config, ErrorLogger* logger)
{
joint.m_lowerLimit = 0.f;
joint.m_upperLimit = 0.f;
joint.m_upperLimit = -1.f;
joint.m_effortLimit = 0.f;
joint.m_velocityLimit = 0.f;
joint.m_jointDamping = 0.f;