#include "BulletMJCFImporter.h" #include "../../ThirdPartyLibs/tinyxml/tinyxml.h" #include "Bullet3Common/b3FileUtils.h" #include #include "../../Utils/b3ResourcePath.h" #include #include #include "../ImportURDFDemo/UrdfParser.h" #include "../ImportURDFDemo/urdfStringSplit.h" #include "../ImportURDFDemo/urdfLexicalCast.h" #include "../ImportObjDemo/LoadMeshFromObj.h" #include "../ImportSTLDemo/LoadMeshFromSTL.h" #include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h" #include "../ImportMeshUtility/b3ImportMeshUtility.h" #include "BulletCollision/CollisionShapes/btCompoundShape.h" #include "BulletCollision/CollisionShapes/btStaticPlaneShape.h" #include "BulletCollision/CollisionShapes/btBoxShape.h" #include "BulletCollision/CollisionShapes/btSphereShape.h" #include "BulletCollision/CollisionShapes/btCapsuleShape.h" #include "BulletCollision/CollisionShapes/btCylinderShape.h" #include "BulletCollision/CollisionShapes/btMultiSphereShape.h" #include "BulletCollision/CollisionShapes/btConvexHullShape.h" #include "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h" #include "BulletCollision/CollisionShapes/btTriangleMesh.h" #include enum ePARENT_LINK_ENUMS { BASE_LINK_INDEX=-1, INVALID_LINK_INDEX=-2 }; static int gUid=0; static bool parseVector4(btVector4& vec4, const std::string& vector_str) { vec4.setZero(); btArray pieces; btArray rgba; btAlignedObjectArray strArray; urdfIsAnyOf(" ", strArray); urdfStringSplit(pieces, vector_str, strArray); for (int i = 0; i < pieces.size(); ++i) { if (!pieces[i].empty()) { rgba.push_back(urdfLexicalCast(pieces[i].c_str())); } } if (rgba.size() != 4) { return false; } vec4.setValue(rgba[0],rgba[1],rgba[2],rgba[3]); return true; } static bool parseVector3(btVector3& vec3, const std::string& vector_str, MJCFErrorLogger* logger, bool lastThree = false) { vec3.setZero(); btArray pieces; btArray rgba; btAlignedObjectArray strArray; urdfIsAnyOf(" ", strArray); urdfStringSplit(pieces, vector_str, strArray); for (int i = 0; i < pieces.size(); ++i) { if (!pieces[i].empty()) { rgba.push_back(urdfLexicalCast(pieces[i].c_str())); } } if (rgba.size() < 3) { logger->reportWarning("Couldn't parse vector3"); return false; } if (lastThree) { vec3.setValue(rgba[rgba.size()-3], rgba[rgba.size()-2], rgba[rgba.size()-1]); } else { vec3.setValue(rgba[0],rgba[1],rgba[2]); } return true; } static bool parseVector6(btVector3& v0, btVector3& v1, const std::string& vector_str, MJCFErrorLogger* logger) { v0.setZero(); v1.setZero(); btArray pieces; btArray values; btAlignedObjectArray strArray; urdfIsAnyOf(" ", strArray); urdfStringSplit(pieces, vector_str, strArray); for (int i = 0; i < pieces.size(); ++i) { if (!pieces[i].empty()) { values.push_back(urdfLexicalCast(pieces[i].c_str())); } } if (values.size() < 6) { logger->reportWarning("Couldn't parse 6 floats"); return false; } v0.setValue(values[0],values[1],values[2]); v1.setValue(values[3],values[4],values[5]); return true; } struct MyMJCFAsset { std::string m_fileName; }; struct BulletMJCFImporterInternalData { GUIHelperInterface* m_guiHelper; struct LinkVisualShapesConverter* m_customVisualShapesConverter; char m_pathPrefix[1024]; std::string m_sourceFileName; // with path std::string m_fileModelName; // without path btHashMap m_assets; btAlignedObjectArray m_models; // std::string m_meshDir; std::string m_textureDir; int m_activeModel; int m_activeBodyUniqueId; //todo: for full MJCF compatibility, we would need a stack of default values int m_defaultCollisionGroup; int m_defaultCollisionMask; btScalar m_defaultCollisionMargin; // joint defaults std::string m_defaultJointLimited; // geom defaults std::string m_defaultGeomRgba; //those collision shapes are deleted by caller (todo: make sure this happens!) btAlignedObjectArray m_allocatedCollisionShapes; BulletMJCFImporterInternalData() :m_activeModel(-1), m_activeBodyUniqueId(-1), m_defaultCollisionGroup(1), m_defaultCollisionMask(1), m_defaultCollisionMargin(0.001)//assume unit meters, margin is 1mm { m_pathPrefix[0] = 0; } std::string sourceFileLocation(TiXmlElement* e) { #if 0 //no C++11 snprintf etc char buf[1024]; snprintf(buf, sizeof(buf), "%s:%i", m_sourceFileName.c_str(), e->Row()); return buf; #else char row[1024]; sprintf(row,"%d",e->Row()); std::string str = m_sourceFileName.c_str() + std::string(":") + std::string(row); return str; #endif } const UrdfLink* getLink(int modelIndex, int linkIndex) const { if (modelIndex>=0 && modelIndexm_links.getAtIndex(linkIndex); if (linkPtrPtr && *linkPtrPtr) { UrdfLink* linkPtr = *linkPtrPtr; return linkPtr; } } return 0; } void parseCompiler(TiXmlElement* root_xml, MJCFErrorLogger* logger) { const char* meshDirStr = root_xml->Attribute("meshdir"); if (meshDirStr) { m_meshDir = meshDirStr; } const char* textureDirStr = root_xml->Attribute("texturedir"); if (textureDirStr) { m_textureDir = textureDirStr; } #if 0 for (TiXmlElement* child_xml = root_xml->FirstChildElement() ; child_xml ; child_xml = child_xml->NextSiblingElement()) { std::string n = child_xml->Value(); } #endif } void parseAssets(TiXmlElement* root_xml, MJCFErrorLogger* logger) { // for (TiXmlElement* child_xml = root_xml->FirstChildElement() ; child_xml ; child_xml = child_xml->NextSiblingElement()) { std::string n = child_xml->Value(); if (n=="mesh") { const char* assetNameStr = child_xml->Attribute("name"); const char* fileNameStr = child_xml->Attribute("file"); if (assetNameStr && fileNameStr) { btHashString assetName = assetNameStr; MyMJCFAsset asset; asset.m_fileName = m_meshDir + fileNameStr; m_assets.insert(assetName,asset); } } } } bool parseDefaults(TiXmlElement* root_xml, MJCFErrorLogger* logger) { bool handled= false; //rudimentary 'default' support, would need more work for better feature coverage for (TiXmlElement* child_xml = root_xml->FirstChildElement() ; child_xml ; child_xml = child_xml->NextSiblingElement()) { std::string n = child_xml->Value(); if (n=="inertial") { } if (n=="asset") { parseAssets(child_xml,logger); } if (n=="joint") { // Other attributes here: // armature="1" // damping="1" // limited="true" if (const char* conTypeStr = child_xml->Attribute("limited")) { m_defaultJointLimited = child_xml->Attribute("limited"); } } if (n=="geom") { //contype, conaffinity const char* conTypeStr = child_xml->Attribute("contype"); if (conTypeStr) { m_defaultCollisionGroup = urdfLexicalCast(conTypeStr); } const char* conAffinityStr = child_xml->Attribute("conaffinity"); if (conAffinityStr) { m_defaultCollisionMask = urdfLexicalCast(conAffinityStr); } const char* rgba = child_xml->Attribute("rgba"); if (rgba) { m_defaultGeomRgba = rgba; } } } handled=true; return handled; } bool parseRootLevel(TiXmlElement* root_xml,MJCFErrorLogger* logger) { for (TiXmlElement* rootxml = root_xml->FirstChildElement() ; rootxml ; rootxml = rootxml->NextSiblingElement()) { bool handled = false; std::string n = rootxml->Value(); if (n=="body") { int modelIndex = m_models.size(); UrdfModel* model = new UrdfModel(); m_models.push_back(model); parseBody(rootxml,modelIndex, INVALID_LINK_INDEX,logger); initTreeAndRoot(*model,logger); handled = true; } if (n=="geom") { int modelIndex = m_models.size(); UrdfModel* modelPtr = new UrdfModel(); m_models.push_back(modelPtr); UrdfLink* linkPtr = new UrdfLink(); linkPtr->m_name = "anonymous"; const char* namePtr = rootxml->Attribute("name"); if (namePtr) { linkPtr->m_name = namePtr; } int linkIndex = modelPtr->m_links.size(); linkPtr->m_linkIndex = linkIndex; modelPtr->m_links.insert(linkPtr->m_name.c_str(),linkPtr); //don't parse geom transform here, it will be inside 'parseGeom' linkPtr->m_linkTransformInWorld.setIdentity(); // modelPtr->m_rootLinks.push_back(linkPtr); btVector3 inertialShift(0,0,0); parseGeom(rootxml,modelIndex, linkIndex,logger,inertialShift); initTreeAndRoot(*modelPtr,logger); handled = true; } if (n=="site") { handled = true; } if (!handled) { logger->reportWarning("Unhandled root element"); logger->reportWarning(n.c_str()); } } return true; } bool parseJoint(TiXmlElement* link_xml, int modelIndex, int parentLinkIndex, int linkIndex, MJCFErrorLogger* logger, const btTransform& parentToLinkTrans, btTransform& jointTransOut) { const char* jType = link_xml->Attribute("type"); const char* limitedStr = link_xml->Attribute("limited"); const char* axisStr = link_xml->Attribute("axis"); const char* posStr = link_xml->Attribute("pos"); const char* ornStr = link_xml->Attribute("quat"); const char* nameStr = link_xml->Attribute("name"); const char* rangeStr = link_xml->Attribute("range"); btTransform jointTrans; jointTrans.setIdentity(); if (posStr) { btVector3 pos; std::string p=posStr; if (parseVector3(pos,p,logger)) { jointTrans.setOrigin(pos); } } if (ornStr) { std::string o = ornStr; btVector4 o4; if (parseVector4(o4,o)) { btQuaternion orn(o4[3],o4[0],o4[1],o4[2]); jointTrans.setRotation(orn); } } btVector3 jointAxis(1,0,0); if (axisStr) { std::string ax = axisStr; parseVector3(jointAxis,ax,logger); } else { logger->reportWarning("joint without axis attribute"); } bool isLimited = false; double range[2] = {1,0}; std::string lim = m_defaultJointLimited; if (limitedStr) { lim = limitedStr; } if (lim=="true") { isLimited = true; //parse the 'range' field btArray pieces; btArray sizes; btAlignedObjectArray strArray; urdfIsAnyOf(" ", strArray); urdfStringSplit(pieces, rangeStr, strArray); for (int i = 0; i < pieces.size(); ++i) { if (!pieces[i].empty()) { sizes.push_back(urdfLexicalCast(pieces[i].c_str())); } } if (sizes.size()==2) { // TODO angle units are in " range[0] = sizes[0] * B3_PI / 180; range[1] = sizes[1] * B3_PI / 180; } else { logger->reportWarning("Expected range[2] in joint with limits"); } } // TODO armature : real, "0" Armature inertia (or rotor inertia) of all // degrees of freedom created by this joint. These are constants added to the // diagonal of the inertia matrix in generalized coordinates. They make the // simulation more stable, and often increase physical realism. This is because // when a motor is attached to the system with a transmission that amplifies // the motor force by c, the inertia of the rotor (i.e. the moving part of the // motor) is amplified by c*c. The same holds for gears in the early stages of // planetary gear boxes. These extra inertias often dominate the inertias of // the robot parts that are represented explicitly in the model, and the // armature attribute is the way to model them. // TODO damping : real, "0" Damping applied to all degrees of // freedom created by this joint. Unlike friction loss // which is computed by the constraint solver, damping is // simply a force linear in velocity. It is included in // the passive forces. Despite this simplicity, larger // damping values can make numerical integrators unstable, // which is why our Euler integrator handles damping // implicitly. See Integration in the Computation chapter. bool jointHandled = false; const UrdfLink* linkPtr = getLink(modelIndex,linkIndex); btTransform parentLinkToJointTransform; parentLinkToJointTransform.setIdentity(); parentLinkToJointTransform = parentToLinkTrans*jointTrans; jointTransOut = jointTrans; UrdfJointTypes ejtype; if (jType) { std::string jointType = jType; if (jointType == "fixed") { ejtype = URDFFixedJoint; jointHandled = true; } if (jointType == "slide") { ejtype = URDFPrismaticJoint; jointHandled = true; } if (jointType == "hinge") { if (isLimited) { ejtype = URDFRevoluteJoint; } else { ejtype = URDFContinuousJoint; } jointHandled = true; } } else { logger->reportWarning("Expected 'type' attribute for joint"); } if (jointHandled) { UrdfJoint* jointPtr = new UrdfJoint(); jointPtr->m_childLinkName=linkPtr->m_name; const UrdfLink* parentLink = getLink(modelIndex,parentLinkIndex); jointPtr->m_parentLinkName =parentLink->m_name; jointPtr->m_localJointAxis=jointAxis; jointPtr->m_parentLinkToJointTransform = parentLinkToJointTransform; jointPtr->m_type = ejtype; int numJoints = m_models[modelIndex]->m_joints.size(); //range jointPtr->m_lowerLimit = range[0]; jointPtr->m_upperLimit = range[1]; if (nameStr) { jointPtr->m_name =nameStr; } else { char jointName[1024]; sprintf(jointName,"joint%d_%d_%d",gUid++,linkIndex,numJoints); jointPtr->m_name =jointName; } m_models[modelIndex]->m_joints.insert(jointPtr->m_name.c_str(),jointPtr); return true; } /* URDFRevoluteJoint=1, URDFPrismaticJoint, URDFContinuousJoint, URDFFloatingJoint, URDFPlanarJoint, URDFFixedJoint, */ return false; } bool parseGeom(TiXmlElement* link_xml, int modelIndex, int linkIndex, MJCFErrorLogger* logger, btVector3& inertialShift) { UrdfLink** linkPtrPtr = m_models[modelIndex]->m_links.getAtIndex(linkIndex); if (linkPtrPtr==0) { logger->reportWarning("Invalide linkindex"); return false; } UrdfLink* linkPtr = *linkPtrPtr; btTransform linkLocalFrame; linkLocalFrame.setIdentity(); bool handledGeomType = false; UrdfGeometry geom; const char* gType = link_xml->Attribute("type"); const char* sz = link_xml->Attribute("size"); const char* posS = link_xml->Attribute("pos"); std::string rgba = m_defaultGeomRgba; if (const char* rgbattr = link_xml->Attribute("rgba")) { rgba = rgbattr; } if (!rgba.empty()) { // "0 0.7 0.7 1" parseVector4(geom.m_localMaterial.m_rgbaColor, rgba); geom.m_hasLocalMaterial = true; geom.m_localMaterial.m_name = rgba; } if (posS) { btVector3 pos(0,0,0); std::string p = posS; if (parseVector3(pos,p,logger)) { linkLocalFrame.setOrigin(pos); } } const char* ornS = link_xml->Attribute("quat"); if (ornS) { std::string ornStr = ornS; btQuaternion orn(0,0,0,1); btVector4 o4; if (parseVector4(o4,ornStr)) { orn.setValue(o4[1],o4[2],o4[3],o4[0]); linkLocalFrame.setRotation(orn); } } if (gType) { std::string geomType = gType; if (geomType == "plane") { geom.m_type = URDF_GEOM_PLANE; geom.m_planeNormal.setValue(0,0,1); btVector3 size(1,1,1); if (sz) { std::string sizeStr = sz; bool lastThree = false; parseVector3(size,sizeStr,logger,lastThree); } geom.m_boxSize = size; handledGeomType = true; } if (geomType == "box") { btVector3 size(1,1,1); if (sz) { std::string sizeStr = sz; bool lastThree = false; parseVector3(size,sizeStr,logger,lastThree); } geom.m_type = URDF_GEOM_BOX; geom.m_boxSize = size; handledGeomType = true; } if (geomType == "sphere") { geom.m_type = URDF_GEOM_SPHERE; if (sz) { geom.m_sphereRadius = urdfLexicalCast(sz); } else { logger->reportWarning("Expected size field (scalar) in sphere geom"); } handledGeomType = true; } if (geomType == "capsule" || geomType == "cylinder") { // geom.m_type = geomType=="cylinder" ? URDF_GEOM_CYLINDER : URDF_GEOM_CAPSULE; btArray pieces; btArray sizes; btAlignedObjectArray strArray; urdfIsAnyOf(" ", strArray); urdfStringSplit(pieces, sz, strArray); for (int i = 0; i < pieces.size(); ++i) { if (!pieces[i].empty()) { sizes.push_back(urdfLexicalCast(pieces[i].c_str())); } } geom.m_capsuleRadius = 0; geom.m_capsuleHalfHeight = 0.f; if (sizes.size()>0) { geom.m_capsuleRadius = sizes[0]; if (sizes.size()>1) { geom.m_capsuleHalfHeight = sizes[1]; } } else { logger->reportWarning("couldn't convert 'size' attribute of capsule geom"); } const char* fromtoStr = link_xml->Attribute("fromto"); geom.m_hasFromTo = false; if (fromtoStr) { geom.m_hasFromTo = true; std::string fromto = fromtoStr; parseVector6(geom.m_capsuleFrom,geom.m_capsuleTo,fromto,logger); inertialShift=0.5*(geom.m_capsuleFrom+geom.m_capsuleTo); handledGeomType = true; } else { if (sizes.size()<2) { logger->reportWarning("capsule without fromto attribute requires 2 sizes (radius and halfheight)"); } else { handledGeomType = true; } } } if (geomType=="mesh") { const char* meshStr = link_xml->Attribute("mesh"); if (meshStr) { MyMJCFAsset* assetPtr = m_assets[meshStr]; if (assetPtr) { geom.m_type = URDF_GEOM_MESH; geom.m_meshFileName = assetPtr->m_fileName; bool exists = findExistingMeshFile( m_sourceFileName, assetPtr->m_fileName, sourceFileLocation(link_xml), &geom.m_meshFileName, &geom.m_meshFileType); handledGeomType = exists; geom.m_meshScale.setValue(1,1,1); //todo: parse mesh scale if (sz) { } } } } if (handledGeomType) { UrdfCollision col; col.m_flags |= URDF_HAS_COLLISION_GROUP; col.m_collisionGroup = m_defaultCollisionGroup; col.m_flags |= URDF_HAS_COLLISION_MASK; col.m_collisionMask = m_defaultCollisionMask; //contype, conaffinity const char* conTypeStr = link_xml->Attribute("contype"); if (conTypeStr) { col.m_flags |= URDF_HAS_COLLISION_GROUP; col.m_collisionGroup = urdfLexicalCast(conTypeStr); } const char* conAffinityStr = link_xml->Attribute("conaffinity"); if (conAffinityStr) { col.m_flags |= URDF_HAS_COLLISION_MASK; col.m_collisionMask = urdfLexicalCast(conAffinityStr); } col.m_geometry = geom; col.m_linkLocalFrame = linkLocalFrame; linkPtr->m_collisionArray.push_back(col); } else { char warn[1024]; sprintf(warn,"Unknown/unhandled geom type: %s", geomType.c_str()); logger->reportWarning(warn); } } else { logger->reportWarning("geom requires type"); } return handledGeomType; } btTransform parseTransform(TiXmlElement* link_xml, MJCFErrorLogger* logger) { btTransform tr; tr.setIdentity(); const char* p = link_xml->Attribute("pos"); if (p) { btVector3 pos(0,0,0); std::string pstr = p; if (parseVector3(pos,pstr,logger)) { tr.setOrigin(pos); } } else { // logger->reportWarning("body should have pos attribute"); } const char* o = link_xml->Attribute("quat"); if (o) { std::string ornstr = o; btVector4 o4; btQuaternion orn(0,0,0,1); if (parseVector4(o4,ornstr)) { orn.setValue(o4[1],o4[2],o4[3],o4[0]);//MuJoCo quats are [w,x,y,z], Bullet uses [x,y,z,w] tr.setRotation(orn); } } else { // logger->reportWarning("body doesn't have quat (orientation) attribute"); } return tr; } double computeVolume(const UrdfLink* linkPtr,MJCFErrorLogger* logger) const { double totalVolume = 0; for (int i=0;im_collisionArray.size();i++) { const UrdfCollision* col = &linkPtr->m_collisionArray[i]; switch (col->m_geometry.m_type) { case URDF_GEOM_SPHERE: { double r = col->m_geometry.m_sphereRadius; totalVolume += 4./3.*SIMD_PI*r*r*r; break; } case URDF_GEOM_BOX: { totalVolume += 8. * col->m_geometry.m_boxSize[0]* col->m_geometry.m_boxSize[1]* col->m_geometry.m_boxSize[2]; break; } case URDF_GEOM_CYLINDER: { //todo break; } case URDF_GEOM_MESH: { //todo (based on mesh bounding box?) break; } case URDF_GEOM_PLANE: { //todo break; } case URDF_GEOM_CAPSULE: { //one sphere double r = col->m_geometry.m_capsuleRadius; totalVolume += 4./3.*SIMD_PI*r*r*r; //and one cylinder of 'height' btScalar h = (col->m_geometry.m_capsuleFrom-col->m_geometry.m_capsuleTo).length(); totalVolume += SIMD_PI*r*r*h; break; } default: { } } } return totalVolume; } UrdfLink* getLink(int modelIndex, int linkIndex) { UrdfLink** linkPtrPtr = m_models[modelIndex]->m_links.getAtIndex(linkIndex); if (linkPtrPtr && *linkPtrPtr) { return *linkPtrPtr; } btAssert(0); return 0; } int createBody(int modelIndex, const char* namePtr) { UrdfModel* modelPtr = m_models[modelIndex]; int orgChildLinkIndex = modelPtr->m_links.size(); UrdfLink* linkPtr = new UrdfLink(); char uniqueLinkName[1024]; sprintf(uniqueLinkName,"link%d",orgChildLinkIndex ); linkPtr->m_name = uniqueLinkName; if (namePtr) { linkPtr->m_name = namePtr; } linkPtr->m_linkIndex = orgChildLinkIndex ; modelPtr->m_links.insert(linkPtr->m_name.c_str(),linkPtr); return orgChildLinkIndex; } bool parseBody(TiXmlElement* link_xml, int modelIndex, int orgParentLinkIndex, MJCFErrorLogger* logger) { int newParentLinkIndex = orgParentLinkIndex; const char* bodyName = link_xml->Attribute("name"); int orgChildLinkIndex = createBody(modelIndex,bodyName); btTransform localInertialFrame; localInertialFrame.setIdentity(); // int curChildLinkIndex = orgChildLinkIndex; std::string bodyN; if (bodyName) { bodyN = bodyName; } else { char anon[1024]; sprintf(anon,"anon%d",gUid++); bodyN = anon; } // btTransform orgLinkTransform = parseTransform(link_xml,logger); btTransform linkTransform = parseTransform(link_xml,logger); UrdfLink* linkPtr = getLink(modelIndex,orgChildLinkIndex); bool massDefined = false; btScalar mass = 0.f; btVector3 localInertiaDiag(0,0,0); // int thisLinkIndex = -2; bool hasJoint = false; btTransform jointTrans; jointTrans.setIdentity(); bool skipFixedJoint = false; for (TiXmlElement* xml = link_xml->FirstChildElement() ; xml ; xml = xml->NextSiblingElement()) { bool handled = false; std::string n = xml->Value(); if (n=="inertial") { // const char* p = xml->Attribute("pos"); if (p) { std::string posStr = p; btVector3 inertialPos(0,0,0); if (parseVector3(inertialPos,posStr,logger)) { localInertialFrame.setOrigin(inertialPos); } } const char* o = xml->Attribute("quat"); { std::string ornStr = o; btQuaternion orn(0,0,0,1); btVector4 o4; if (parseVector4(o4,ornStr)) { orn.setValue(o4[1],o4[2],o4[3],o4[0]); localInertialFrame.setRotation(orn); } } const char* m = xml->Attribute("mass"); if (m) { mass = urdfLexicalCast(m); } const char* i = xml->Attribute("diaginertia"); if (i) { std::string istr = i; parseVector3(localInertiaDiag,istr,logger); } massDefined = true; handled = true; } if (n=="joint") { if (!hasJoint) { const char* jType = xml->Attribute("type"); std::string jointType = jType? jType:""; if (newParentLinkIndex!=INVALID_LINK_INDEX || jointType!="free") { if (newParentLinkIndex==INVALID_LINK_INDEX) { int newRootLinkIndex = createBody(modelIndex,0); UrdfLink* rootLink = getLink(modelIndex,newRootLinkIndex); rootLink->m_inertia.m_mass = 0; rootLink->m_linkTransformInWorld.setIdentity(); newParentLinkIndex = newRootLinkIndex; } int newLinkIndex = createBody(modelIndex,0); parseJoint(xml,modelIndex,newParentLinkIndex, newLinkIndex,logger,linkTransform,jointTrans); //getLink(modelIndex,newLinkIndex)->m_linkTransformInWorld = jointTrans*linkTransform; linkTransform = jointTrans.inverse(); newParentLinkIndex = newLinkIndex; //newParentLinkIndex, curChildLinkIndex hasJoint = true; handled = true; } } else { int newLinkIndex = createBody(modelIndex,0); btTransform joint2nextjoint = jointTrans.inverse(); btTransform unused; parseJoint(xml,modelIndex,newParentLinkIndex, newLinkIndex,logger,joint2nextjoint,unused); newParentLinkIndex = newLinkIndex; //todo: compute relative joint transforms (if any) and append to linkTransform hasJoint = true; handled = true; } } if (n == "geom") { btVector3 inertialShift(0,0,0); parseGeom(xml,modelIndex, orgChildLinkIndex , logger,inertialShift); if (!massDefined) { localInertialFrame.setOrigin(inertialShift); } handled = true; } //recursive if (n=="body") { parseBody(xml,modelIndex,orgChildLinkIndex,logger); handled = true; } if (n=="light") { handled = true; } if (!handled) { char warn[1024]; std::string n = xml->Value(); sprintf(warn,"Unknown/unhandled field: %s", n.c_str()); logger->reportWarning(warn); } } linkPtr->m_linkTransformInWorld = linkTransform; if ((newParentLinkIndex != INVALID_LINK_INDEX) && !skipFixedJoint) { //linkPtr->m_linkTransformInWorld.setIdentity(); //default to 'fixed' joint UrdfJoint* jointPtr = new UrdfJoint(); jointPtr->m_childLinkName=linkPtr->m_name; const UrdfLink* parentLink = getLink(modelIndex,newParentLinkIndex); jointPtr->m_parentLinkName =parentLink->m_name; jointPtr->m_localJointAxis.setValue(1,0,0); jointPtr->m_parentLinkToJointTransform = linkTransform; jointPtr->m_type = URDFFixedJoint; char jointName[1024]; sprintf(jointName,"jointfix_%d_%d",gUid++,newParentLinkIndex); jointPtr->m_name =jointName; m_models[modelIndex]->m_joints.insert(jointPtr->m_name.c_str(),jointPtr); } //check mass/inertia if (!massDefined) { double density = 1000; double volume = computeVolume(linkPtr,logger); mass = density * volume; } linkPtr->m_inertia.m_linkLocalFrame = localInertialFrame;// = jointTrans.inverse(); linkPtr->m_inertia.m_mass = mass; return true; } void recurseAddChildLinks(UrdfModel* model, UrdfLink* link) { for (int i=0;im_childLinks.size();i++) { int linkIndex = model->m_links.size(); link->m_childLinks[i]->m_linkIndex = linkIndex; const char* linkName = link->m_childLinks[i]->m_name.c_str(); model->m_links.insert(linkName,link->m_childLinks[i]); } for (int i=0;im_childLinks.size();i++) { recurseAddChildLinks(model,link->m_childLinks[i]); } } bool initTreeAndRoot(UrdfModel& model, MJCFErrorLogger* logger) { // every link has children links and joints, but no parents, so we create a // local convenience data structure for keeping child->parent relations btHashMap parentLinkTree; // loop through all joints, for every link, assign children links and children joints for (int i=0;im_parentLinkName; std::string child_link_name = joint->m_childLinkName; if (parent_link_name.empty() || child_link_name.empty()) { logger->reportError("parent link or child link is empty for joint"); logger->reportError(joint->m_name.c_str()); return false; } UrdfLink** childLinkPtr = model.m_links.find(joint->m_childLinkName.c_str()); if (!childLinkPtr) { logger->reportError("Cannot find child link for joint "); logger->reportError(joint->m_name.c_str()); return false; } UrdfLink* childLink = *childLinkPtr; UrdfLink** parentLinkPtr = model.m_links.find(joint->m_parentLinkName.c_str()); if (!parentLinkPtr) { logger->reportError("Cannot find parent link for a joint"); logger->reportError(joint->m_name.c_str()); return false; } UrdfLink* parentLink = *parentLinkPtr; childLink->m_parentLink = parentLink; childLink->m_parentJoint = joint; parentLink->m_childJoints.push_back(joint); parentLink->m_childLinks.push_back(childLink); parentLinkTree.insert(childLink->m_name.c_str(),parentLink->m_name.c_str()); } } //search for children that have no parent, those are 'root' for (int i=0;im_linkIndex = i; if (!link->m_parentLink) { model.m_rootLinks.push_back(link); } } } if (model.m_rootLinks.size()>1) { logger->reportWarning("URDF file with multiple root links found"); } if (model.m_rootLinks.size()==0) { logger->reportError("URDF without root link found"); return false; } //re-index the link indices so parent indices are always smaller than child indices btAlignedObjectArray links; links.resize(model.m_links.size()); for (int i=0;im_linkIndex = linkIndex; model.m_links.insert(rootLink->m_name.c_str(),rootLink); recurseAddChildLinks(&model, rootLink); } return true; } }; BulletMJCFImporter::BulletMJCFImporter(struct GUIHelperInterface* helper, LinkVisualShapesConverter* customConverter) { m_data = new BulletMJCFImporterInternalData(); m_data->m_guiHelper = helper; m_data->m_customVisualShapesConverter = customConverter; } BulletMJCFImporter::~BulletMJCFImporter() { delete m_data; } bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger, bool forceFixedBase) { if (strlen(fileName)==0) return false; //int argc=0; char relativeFileName[1024]; b3FileUtils fu; //bool fileFound = fu.findFile(fileName, relativeFileName, 1024); bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024)>0); m_data->m_sourceFileName = relativeFileName; std::string xml_string; m_data->m_pathPrefix[0] = 0; if (!fileFound){ std::cerr << "MJCF file not found" << std::endl; return false; } else { int maxPathLen = 1024; fu.extractPath(relativeFileName,m_data->m_pathPrefix,maxPathLen); std::fstream xml_file(relativeFileName, std::fstream::in); while ( xml_file.good()) { std::string line; std::getline( xml_file, line); xml_string += (line + "\n"); } xml_file.close(); if (parseMJCFString(xml_string.c_str(), logger)) { return true; } } return false; } bool BulletMJCFImporter::parseMJCFString(const char* xmlText, MJCFErrorLogger* logger) { TiXmlDocument xml_doc; xml_doc.Parse(xmlText); if (xml_doc.Error()) { logger->reportError(xml_doc.ErrorDesc()); xml_doc.ClearError(); return false; } TiXmlElement *mujoco_xml = xml_doc.FirstChildElement("mujoco"); if (!mujoco_xml) { logger->reportWarning("Cannot find root element"); return false; } const char* modelName = mujoco_xml->Attribute("model"); if (modelName) { m_data->m_fileModelName = modelName; } //,