element.text = "../materials/textures/torso_diffuse_unplugged_mit.jpg" dae.write(inFile) mit.convertMeshTo(inFile, ".obj") colladaFile = os.path.splitext(inFile)[0] + ".vtm" convertCollada.colladaToPolyData(inFile, colladaFile) os.chdir(originalDirectory) for inFile in glob(os.path.join(meshesDirectory, "*.obj")): if "chull" not in inFile: mit.createConvexHullMesh(inFile) for inFile in glob(os.path.join(meshesDirectory, "*.obj")): mit.convertMeshTo(inFile, ".wrl") mit.xacro(full_mesh_xacro_path, full_mesh_urdf_path) urdf = etree.parse(full_mesh_urdf_path) mit.renameJoints(urdf, jointNameMap) # Weld dummy lwy joints mit.weldJoint(urdf, "l_arm_lwy") mit.weldJoint(urdf, "r_arm_lwy") mit.replaceMeshPaths(urdf, "package://atlas_v4/meshes") mit.useObjMeshes(urdf) mit.addFrame(urdf, "l_foot_sole", "l_foot", "0.0426 0.0017 -0.07645", "0 0 0") mit.addFrame(urdf, "r_foot_sole", "r_foot", "0.0426 -0.0017 -0.07645", "0 0 0") mit.addFrame(urdf, "l_foot_toe", "l_foot", "0.1728 0.0017 -0.07645", "0 0 0") mit.addFrame(urdf, "r_foot_toe", "r_foot", "0.1728 -0.0017 -0.07645", "0 0 0")
#!/usr/bin/python import os drc_base_path = os.getenv("DRC_BASE") import sys sys.path.append( os.path.join(drc_base_path, "software", "models", "model_transformation")) import mitUrdfUtils as mit os.chdir(os.path.dirname(os.path.realpath(__file__))) mit.xacro("atlas_v4_LR_RR.xacro", "../model_LR_RR.urdf", verbose=True) mit.xacro("atlas_v4_minimal_contact.xacro", "../model_minimal_contact.urdf", verbose=True) mit.xacro("atlas_v4_convex_hull_open_hands.xacro", "../model_convex_hull.urdf", verbose=True) mit.xacro("atlas_v4_convex_hull_fingers.xacro", "../model_convex_hull_fingers.urdf", verbose=True) mit.xacro("atlas_v4_convex_hull_closed_hands.xacro", "../model_convex_hull_closed_hands.urdf", verbose=True)
element.text = '../materials/textures/torso_diffuse_unplugged_mit.jpg' dae.write(inFile) mit.convertMeshTo(inFile, ".obj") colladaFile = os.path.splitext(inFile)[0] + '.vtm' convertCollada.colladaToPolyData(inFile, colladaFile) os.chdir(originalDirectory) for inFile in glob(os.path.join(meshesDirectory, "*.obj")): if "chull" not in inFile: mit.createConvexHullMesh(inFile) for inFile in glob(os.path.join(meshesDirectory, "*.obj")): mit.convertMeshTo(inFile, ".wrl") mit.xacro(full_mesh_xacro_path, full_mesh_urdf_path) urdf = etree.parse(full_mesh_urdf_path) mit.renameJoints(urdf, jointNameMap) mit.replaceMeshPaths(urdf, "package://atlas_v5/meshes") mit.useObjMeshes(urdf) mit.addFrame(urdf, "l_foot_sole", "l_foot", "0.0426 0.0017 -0.07645", "0 0 0") mit.addFrame(urdf, "r_foot_sole", "r_foot", "0.0426 -0.0017 -0.07645", "0 0 0") mit.addFrame(urdf, "l_foot_toe", "l_foot", "0.1728 0.0017 -0.07645", "0 0 0") mit.addFrame(urdf, "r_foot_toe", "r_foot", "0.1728 -0.0017 -0.07645", "0 0 0") mit.removeCollisions(urdf, ['mtorso', 'ltorso', 'l_talus', 'r_talus']) armLinkNames = ['clav', 'scap', 'uarm', 'larm', 'ufarm', 'lfarm', 'hand'] for armLinkName in armLinkNames:
#!/usr/bin/python import os drc_base_path = os.getenv("DRC_BASE") import sys sys.path.append(os.path.join(drc_base_path, "software", "models", "model_transformation")) import mitUrdfUtils as mit os.chdir(os.path.dirname(os.path.realpath(__file__))) mit.xacro("atlas_v4_LR_RR.xacro", "../model_LR_RR.urdf", verbose=True) mit.xacro("atlas_v4_minimal_contact.xacro", "../model_minimal_contact.urdf", verbose=True) mit.xacro("atlas_v4_convex_hull_open_hands.xacro", "../model_convex_hull.urdf", verbose=True) mit.xacro("atlas_v4_convex_hull_fingers.xacro", "../model_convex_hull_fingers.urdf", verbose=True) mit.xacro("atlas_v4_convex_hull_closed_hands.xacro", "../model_convex_hull_closed_hands.urdf", verbose=True)
mit.convertMeshTo(inFile, ".obj") mit.convertMeshTo(inFile, ".wrl") for directory in [collisionMeshesDirectory, articulatedCollisionMeshesDirectory]: for inFile in glob(os.path.join(directory, "*.obj")): if "chull" not in inFile: mit.createConvexHullMesh(inFile) for inFile in glob(os.path.join(directory, "*.wrl")): if "chull" not in inFile: mit.createConvexHullMesh(inFile) # Expand all includes to ensure proper editing of mesh filenames below tmp = tempfile.NamedTemporaryFile() mit.xacro(original_urdf_path, tmp.name, includes_only=True, recursive_includes=True) # Load urdf urdf = etree.parse(tmp.name) # Use .obj meshes mit.useObjMeshes(urdf) # Use convex hull meshes for collisions mit.useConvexHullMeshes(urdf) # Generate full urdf urdf.write(urdf_path, pretty_print=True) # Generate no-collision urdf no_collision_urdf = copy.deepcopy(urdf)
for directory in [ collisionMeshesDirectory, articulatedCollisionMeshesDirectory ]: for inFile in glob(os.path.join(directory, "*.obj")): if "chull" not in inFile: mit.createConvexHullMesh(inFile) for inFile in glob(os.path.join(directory, "*.wrl")): if "chull" not in inFile: mit.createConvexHullMesh(inFile) # Expand all includes to ensure proper editing of mesh filenames below tmp = tempfile.NamedTemporaryFile() mit.xacro(original_urdf_path, tmp.name, includes_only=True, recursive_includes=True) # Load urdf urdf = etree.parse(tmp.name) # Use .obj meshes mit.useObjMeshes(urdf) # Use convex hull meshes for collisions mit.useConvexHullMeshes(urdf) # Generate full urdf urdf.write(urdf_path, pretty_print=True) # Generate no-collision urdf