Initial Commit
5
.gitignore
vendored
Normal file
|
@ -0,0 +1,5 @@
|
|||
__pycache__
|
||||
*.pyc
|
||||
launch.json
|
||||
settings.json
|
||||
|
3
.gitmodules
vendored
Normal file
|
@ -0,0 +1,3 @@
|
|||
[submodule "Joint2Graphviz"]
|
||||
path = Joint2Graphviz
|
||||
url = https://github.com/yanshil/Joint2Graphviz.git
|
10
Bullet_URDF_Exporter/Bullet_URDF_Exporter.manifest
Normal file
|
@ -0,0 +1,10 @@
|
|||
{
|
||||
"autodeskProduct": "Fusion360",
|
||||
"type": "script",
|
||||
"author": "yanshil",
|
||||
"description": {
|
||||
"": "Export PyBullet adaptive stl and URDF file"
|
||||
},
|
||||
"supportedOS": "windows|mac",
|
||||
"editEnabled": true
|
||||
}
|
98
Bullet_URDF_Exporter/Bullet_URDF_Exporter.py
Normal file
|
@ -0,0 +1,98 @@
|
|||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Export PyBullet adaptive stl and URDF file
|
||||
|
||||
@syuntoku
|
||||
@yanshil
|
||||
"""
|
||||
|
||||
import adsk, adsk.core, adsk.fusion, traceback
|
||||
import os
|
||||
from .utils import utils
|
||||
from .core import Link, Joint, Write
|
||||
|
||||
"""
|
||||
# length unit is 'cm' and inertial unit is 'kg/cm^2'
|
||||
# If there is no 'body' in the root component, maybe the corrdinates are wrong.
|
||||
"""
|
||||
|
||||
# joint effort: 100
|
||||
# joint velocity: 100
|
||||
# supports "Revolute", "Rigid" and "Slider" joint types
|
||||
|
||||
# I'm not sure how prismatic joint acts if there is no limit in fusion model
|
||||
|
||||
def run(context):
|
||||
ui = None
|
||||
success_msg = 'Successfully create URDF file'
|
||||
msg = success_msg
|
||||
|
||||
try:
|
||||
# --------------------
|
||||
# initialize
|
||||
app = adsk.core.Application.get()
|
||||
ui = app.userInterface
|
||||
product = app.activeProduct
|
||||
design = adsk.fusion.Design.cast(product)
|
||||
|
||||
title = 'Fusion2URDF'
|
||||
if not design:
|
||||
ui.messageBox('No active Fusion design', title)
|
||||
return
|
||||
|
||||
root = design.rootComponent # root component
|
||||
components = design.allComponents
|
||||
|
||||
# set the names
|
||||
package_name = 'fusion2urdf'
|
||||
robot_name = root.name.split()[0].lower()
|
||||
save_dir = utils.file_dialog(ui)
|
||||
if save_dir == False:
|
||||
ui.messageBox('Fusion2URDF was canceled', title)
|
||||
return 0
|
||||
|
||||
save_dir = save_dir + '/' + robot_name
|
||||
try: os.mkdir(save_dir)
|
||||
except: pass
|
||||
|
||||
## Set "Do not capture design history"
|
||||
design.designType = adsk.fusion.DesignTypes.DirectDesignType
|
||||
|
||||
# --------------------
|
||||
# set dictionaries
|
||||
|
||||
# Generate joints_dict. All joints are related to root.
|
||||
joints_dict, msg = Joint.make_joints_dict(root, msg)
|
||||
if msg != success_msg:
|
||||
ui.messageBox(msg, title)
|
||||
return 0
|
||||
|
||||
# Generate inertial_dict
|
||||
inertial_dict, msg = Link.make_inertial_dict(root, msg)
|
||||
if msg != success_msg:
|
||||
ui.messageBox(msg, title)
|
||||
return 0
|
||||
elif not 'base_link' in inertial_dict:
|
||||
msg = 'There is no base_link. Please set base_link and run again.'
|
||||
ui.messageBox(msg, title)
|
||||
return 0
|
||||
|
||||
links_xyz_dict = {}
|
||||
|
||||
# --------------------
|
||||
# Generate URDF
|
||||
Write.write_urdf(joints_dict, links_xyz_dict, inertial_dict, package_name, save_dir, robot_name)
|
||||
Write.write_hello_pybullet(robot_name, save_dir)
|
||||
|
||||
# Generate STl files
|
||||
utils.export_stl(app, save_dir)
|
||||
# utils.copy_occs(root)
|
||||
# utils.export_stl(design, save_dir, components)
|
||||
# utils.export_stl(app, save_dir, components)
|
||||
# utils.export_stl(design, save_dir, components)
|
||||
# utils.export_stl(app, save_dir)
|
||||
ui.messageBox(msg, title)
|
||||
|
||||
except:
|
||||
if ui:
|
||||
ui.messageBox('Failed:\n{}'.format(traceback.format_exc()))
|
461
Bullet_URDF_Exporter/core/Joint.py
Normal file
|
@ -0,0 +1,461 @@
|
|||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Export joint infos to XML from Fusion 360
|
||||
|
||||
@syuntoku
|
||||
@yanshil
|
||||
"""
|
||||
|
||||
import adsk, re, traceback
|
||||
from xml.etree.ElementTree import Element, SubElement
|
||||
from ..utils import utils
|
||||
|
||||
class Joint:
|
||||
def __init__(self, name, xyz, axis, parent, child, joint_type, upper_limit, lower_limit):
|
||||
"""
|
||||
Attributes
|
||||
----------
|
||||
name: str
|
||||
name of the joint
|
||||
type: str
|
||||
type of the joint(ex: rev)
|
||||
xyz: [x, y, z]
|
||||
coordinate of the joint
|
||||
axis: [x, y, z]
|
||||
coordinate of axis of the joint
|
||||
parent: str
|
||||
parent link
|
||||
child: str
|
||||
child link
|
||||
joint_xml: str
|
||||
generated xml describing about the joint
|
||||
tran_xml: str
|
||||
generated xml describing about the transmission
|
||||
"""
|
||||
self.name = name
|
||||
self.type = joint_type
|
||||
self.xyz = xyz
|
||||
self.parent = parent
|
||||
self.child = child
|
||||
self.joint_xml = None
|
||||
self.tran_xml = None
|
||||
self.axis = axis # for 'revolute' and 'continuous'
|
||||
self.upper_limit = upper_limit # for 'revolute' and 'prismatic'
|
||||
self.lower_limit = lower_limit # for 'revolute' and 'prismatic'
|
||||
|
||||
def make_joint_xml(self):
|
||||
"""
|
||||
Generate the joint_xml and hold it by self.joint_xml
|
||||
"""
|
||||
joint = Element('joint')
|
||||
joint.attrib = {'name':self.name, 'type':self.type}
|
||||
|
||||
origin = SubElement(joint, 'origin')
|
||||
origin.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
parent = SubElement(joint, 'parent')
|
||||
parent.attrib = {'link':self.parent}
|
||||
child = SubElement(joint, 'child')
|
||||
child.attrib = {'link':self.child}
|
||||
if self.type == 'revolute' or self.type == 'continuous' or self.type == 'prismatic':
|
||||
axis = SubElement(joint, 'axis')
|
||||
axis.attrib = {'xyz':' '.join([str(_) for _ in self.axis])}
|
||||
if self.type == 'revolute' or self.type == 'prismatic':
|
||||
limit = SubElement(joint, 'limit')
|
||||
limit.attrib = {'upper': str(self.upper_limit), 'lower': str(self.lower_limit),
|
||||
'effort': '100', 'velocity': '100'}
|
||||
|
||||
self.joint_xml = "\n".join(utils.prettify(joint).split("\n")[1:])
|
||||
|
||||
def make_transmission_xml(self):
|
||||
"""
|
||||
Generate the tran_xml and hold it by self.tran_xml
|
||||
|
||||
|
||||
Notes
|
||||
-----------
|
||||
mechanicalTransmission: 1
|
||||
type: transmission interface/SimpleTransmission
|
||||
hardwareInterface: PositionJointInterface
|
||||
"""
|
||||
|
||||
tran = Element('transmission')
|
||||
tran.attrib = {'name':self.name + '_tran'}
|
||||
|
||||
joint_type = SubElement(tran, 'type')
|
||||
joint_type.text = 'transmission_interface/SimpleTransmission'
|
||||
|
||||
joint = SubElement(tran, 'joint')
|
||||
joint.attrib = {'name':self.name}
|
||||
hardwareInterface_joint = SubElement(joint, 'hardwareInterface')
|
||||
hardwareInterface_joint.text = 'PositionJointInterface'
|
||||
|
||||
actuator = SubElement(tran, 'actuator')
|
||||
actuator.attrib = {'name':self.name + '_actr'}
|
||||
hardwareInterface_actr = SubElement(actuator, 'hardwareInterface')
|
||||
hardwareInterface_actr.text = 'PositionJointInterface'
|
||||
mechanicalReduction = SubElement(actuator, 'mechanicalReduction')
|
||||
mechanicalReduction.text = '1'
|
||||
|
||||
self.tran_xml = "\n".join(utils.prettify(tran).split("\n")[1:])
|
||||
|
||||
########## Nested-component support ##########
|
||||
|
||||
def make_joints_dict(root, msg):
|
||||
"""
|
||||
joints_dict holds parent, axis and xyz informatino of the joints
|
||||
|
||||
|
||||
Parameters
|
||||
----------
|
||||
root: adsk.fusion.Design.cast(product)
|
||||
Root component
|
||||
msg: str
|
||||
Tell the status
|
||||
|
||||
Returns
|
||||
----------
|
||||
joints_dict:
|
||||
{name: {type, axis, upper_limit, lower_limit, parent, child, xyz}}
|
||||
msg: str
|
||||
Tell the status
|
||||
"""
|
||||
|
||||
joint_type_list = [
|
||||
'fixed', 'revolute', 'prismatic', 'Cylinderical',
|
||||
'PinSlot', 'Planner', 'Ball'] # these are the names in urdf
|
||||
|
||||
joints_dict = {}
|
||||
|
||||
for joint in root.joints:
|
||||
if joint.isLightBulbOn :
|
||||
joint_dict = {}
|
||||
joint_type = joint_type_list[joint.jointMotion.jointType]
|
||||
joint_dict['type'] = joint_type
|
||||
|
||||
# switch by the type of the joint
|
||||
joint_dict['axis'] = [0, 0, 0]
|
||||
joint_dict['upper_limit'] = 0.0
|
||||
joint_dict['lower_limit'] = 0.0
|
||||
|
||||
# support "Revolute", "Rigid" and "Slider"
|
||||
if joint_type == 'revolute':
|
||||
joint_dict['axis'] = [round(i, 6) for i in \
|
||||
joint.jointMotion.rotationAxisVector.asArray()] ## In Fusion, exported axis is normalized.
|
||||
max_enabled = joint.jointMotion.rotationLimits.isMaximumValueEnabled
|
||||
min_enabled = joint.jointMotion.rotationLimits.isMinimumValueEnabled
|
||||
if max_enabled and min_enabled:
|
||||
joint_dict['upper_limit'] = round(joint.jointMotion.rotationLimits.maximumValue, 6)
|
||||
joint_dict['lower_limit'] = round(joint.jointMotion.rotationLimits.minimumValue, 6)
|
||||
elif max_enabled and not min_enabled:
|
||||
msg = joint.name + 'is not set its lower limit. Please set it and try again.'
|
||||
break
|
||||
elif not max_enabled and min_enabled:
|
||||
msg = joint.name + 'is not set its upper limit. Please set it and try again.'
|
||||
break
|
||||
else: # if there is no angle limit
|
||||
joint_dict['type'] = 'continuous'
|
||||
|
||||
elif joint_type == 'prismatic':
|
||||
joint_dict['axis'] = [round(i, 6) for i in \
|
||||
joint.jointMotion.slideDirectionVector.asArray()] # Also normalized
|
||||
max_enabled = joint.jointMotion.slideLimits.isMaximumValueEnabled
|
||||
min_enabled = joint.jointMotion.slideLimits.isMinimumValueEnabled
|
||||
if max_enabled and min_enabled:
|
||||
joint_dict['upper_limit'] = round(joint.jointMotion.slideLimits.maximumValue/100, 6)
|
||||
joint_dict['lower_limit'] = round(joint.jointMotion.slideLimits.minimumValue/100, 6)
|
||||
elif max_enabled and not min_enabled:
|
||||
msg = joint.name + 'is not set its lower limit. Please set it and try again.'
|
||||
break
|
||||
elif not max_enabled and min_enabled:
|
||||
msg = joint.name + 'is not set its upper limit. Please set it and try again.'
|
||||
break
|
||||
elif joint_type == 'fixed':
|
||||
pass
|
||||
|
||||
|
||||
def get_parent(occ):
|
||||
# function to find the root component of the joint. This is necessary for the correct component name in the urdf file
|
||||
if occ.assemblyContext != None:
|
||||
#print(occ.name)
|
||||
occ = get_parent(occ.assemblyContext)
|
||||
return occ
|
||||
|
||||
if joint.occurrenceTwo != None and joint.occurrenceOne != None and joint.occurrenceOne.isLightBulbOn:
|
||||
parent_occ = get_parent(joint.occurrenceTwo)
|
||||
# print("Joint 1 Parent: " +parent_occ.name)
|
||||
if "base_link" in parent_occ.name:
|
||||
joint_dict['parent'] = 'base_link'
|
||||
base_link = parent_occ
|
||||
else:
|
||||
joint_dict['parent'] = re.sub('[ :()]', '_', parent_occ.name)
|
||||
# print("Joint 2: " +joint.occurrenceOne.name)
|
||||
parent_occ = get_parent(joint.occurrenceOne)
|
||||
# print("Joint 2 Parent: " +parent_occ.name)
|
||||
joint_dict['child'] = re.sub('[ :()]', '_', parent_occ.name)
|
||||
else:
|
||||
break
|
||||
|
||||
def getJointOriginWorldCoordinates(joint :adsk.fusion.Joint):
|
||||
# Function to transform the joint origin coordinates which are in the component context into world coordinates
|
||||
# Thanky you for the help in the fusion forum
|
||||
# https://forums.autodesk.com/t5/fusion-360-api-and-scripts/how-to-get-the-joint-origin-in-world-context/m-p/10011971/highlight/false#M12401
|
||||
def getMatrixFromRoot(root_occ) -> adsk.core.Matrix3D:
|
||||
mat = adsk.core.Matrix3D.create()
|
||||
|
||||
occ = adsk.fusion.Occurrence.cast(root_occ)
|
||||
if not occ:
|
||||
return mat # root
|
||||
|
||||
def getParentOccs(joint):
|
||||
occs_list = []
|
||||
|
||||
if joint != None:
|
||||
occs_list.append(joint)
|
||||
|
||||
if joint.assemblyContext != None:
|
||||
occs_list = occs_list + getParentOccs(joint.assemblyContext)
|
||||
|
||||
return occs_list
|
||||
|
||||
occs = getParentOccs(root_occ)
|
||||
mat3ds = [occ.transform for occ in occs if occ!= None]
|
||||
#mat3ds.reverse()
|
||||
for mat3d in mat3ds:
|
||||
mat.transformBy(mat3d)
|
||||
return mat
|
||||
|
||||
# mat :adsk.core.Matrix3D = getMatrixFromRoot(joint.occurrenceOne)
|
||||
# ori1 :adsk.core.Point3D = joint.geometryOrOriginOne.origin.copy()
|
||||
# ori1.transformBy(mat)
|
||||
|
||||
mat = getMatrixFromRoot(joint.occurrenceTwo)
|
||||
ori2 :adsk.core.Point3D = joint.geometryOrOriginTwo.origin.copy()
|
||||
ori2.transformBy(mat)
|
||||
return ori2 #ori1,
|
||||
|
||||
try:
|
||||
#xyz_of_joint = getJointOriginWorldCoordinates(joint)
|
||||
xyz_of_joint = joint.geometryOrOriginTwo.origin
|
||||
joint_dict['xyz'] = [round(i / 100.0, 6) for i in xyz_of_joint.asArray()] # converted to meter
|
||||
#print(f"xyz : {joint_dict['xyz']}")
|
||||
|
||||
except:
|
||||
print('Failed:\n{}'.format(traceback.format_exc()))
|
||||
try:
|
||||
if type(joint.geometryOrOriginTwo)==adsk.fusion.JointOrigin:
|
||||
data = joint.geometryOrOriginTwo.geometry.origin.asArray()
|
||||
else:
|
||||
data = joint.geometryOrOriginTwo.origin.asArray()
|
||||
joint_dict['xyz'] = [round(i / 100.0, 6) for i in data] # converted to meter
|
||||
except:
|
||||
msg = joint.name + " doesn't have joint origin. Please set it and run again."
|
||||
break
|
||||
|
||||
joints_dict[joint.name] = joint_dict
|
||||
# msg += str(joints_dict)
|
||||
return joints_dict, msg
|
||||
# def make_joints_dict(root, msg):
|
||||
# """
|
||||
# joints_dict holds parent, axis and xyz informatino of the joints
|
||||
|
||||
|
||||
# Parameters
|
||||
# ----------
|
||||
# root: adsk.fusion.Design.cast(product)
|
||||
# Root component
|
||||
# msg: str
|
||||
# Tell the status
|
||||
|
||||
# Returns
|
||||
# ----------
|
||||
# joints_dict:
|
||||
# {name: {type, axis, upper_limit, lower_limit, parent, child, xyz}}
|
||||
# msg: str
|
||||
# Tell the status
|
||||
# """
|
||||
|
||||
# joints_dict = {}
|
||||
|
||||
# ## Root joints
|
||||
# for joint in root.joints:
|
||||
# joint_dict = get_joint_dict(joint)
|
||||
# if type(joint_dict) is dict:
|
||||
# key = utils.get_valid_filename(joint.name)
|
||||
# joints_dict[key] = joint_dict
|
||||
# else: ## Error happens and throw an msg
|
||||
# msg = joint_dict
|
||||
|
||||
# ## Traverse non-root nested components
|
||||
# nonroot_joints_dict = traverseAssembly(root.occurrences.asList, 1)
|
||||
|
||||
# ## Combine
|
||||
# joints_dict.update(nonroot_joints_dict)
|
||||
|
||||
# return joints_dict, msg
|
||||
|
||||
|
||||
# ## TODO: Make msg more accurate and elegent
|
||||
# def traverseAssembly(occurrences, currentLevel, joints_dict={}, msg='Successfully create URDF file'):
|
||||
|
||||
# for i in range(0, occurrences.count):
|
||||
# occ = occurrences.item(i)
|
||||
|
||||
# if occ.component.joints.count > 0:
|
||||
# for joint in occ.component.joints:
|
||||
# ass_joint = joint.createForAssemblyContext(occ)
|
||||
# joint_dict = get_joint_dict(ass_joint)
|
||||
# if type(joint_dict) is dict:
|
||||
# key = utils.get_valid_filename(occ.fullPathName) + '_' + joint.name
|
||||
# joints_dict[key] = joint_dict
|
||||
# else: ## Error happens and throw an msg
|
||||
# msg = joint_dict
|
||||
# # tmp_joints_dict, msg = make_joints_dict(ass_joint, msg)
|
||||
# if msg != 'Successfully create URDF file':
|
||||
# print('Check Component: ' + comp.name + '\t Joint: ' + joint.name)
|
||||
# return 0
|
||||
|
||||
# # print('Level {} {}: Joint {}.'.format(currentLevel, occ.name, ass_joint.name))
|
||||
# else:
|
||||
# pass
|
||||
# # print('Level {} {} has no joints.'.format(currentLevel, occ.name))
|
||||
|
||||
# if occ.childOccurrences:
|
||||
# joints_dict = traverseAssembly(occ.childOccurrences, currentLevel + 1, joints_dict, msg)
|
||||
|
||||
# return joints_dict
|
||||
|
||||
|
||||
|
||||
# def get_joint_dict(joint):
|
||||
# joint_type_list = [
|
||||
# 'fixed', 'revolute', 'prismatic', 'Cylinderical',
|
||||
# 'PinSlot', 'Planner', 'Ball'] # these are the names in urdf
|
||||
|
||||
# joint_dict = {}
|
||||
# joint_type = joint_type_list[joint.jointMotion.jointType]
|
||||
# joint_dict['type'] = joint_type
|
||||
|
||||
# # swhich by the type of the joint
|
||||
# joint_dict['axis'] = [0, 0, 0]
|
||||
# joint_dict['upper_limit'] = 0.0
|
||||
# joint_dict['lower_limit'] = 0.0
|
||||
|
||||
# # support "Revolute", "Rigid" and "Slider"
|
||||
# if joint_type == 'revolute':
|
||||
# joint_dict['axis'] = [round(i, 6) for i in \
|
||||
# joint.jointMotion.rotationAxisVector.asArray()] ## In Fusion, exported axis is normalized.
|
||||
# max_enabled = joint.jointMotion.rotationLimits.isMaximumValueEnabled
|
||||
# min_enabled = joint.jointMotion.rotationLimits.isMinimumValueEnabled
|
||||
# if max_enabled and min_enabled:
|
||||
# joint_dict['upper_limit'] = round(joint.jointMotion.rotationLimits.maximumValue, 6)
|
||||
# joint_dict['lower_limit'] = round(joint.jointMotion.rotationLimits.minimumValue, 6)
|
||||
# elif max_enabled and not min_enabled:
|
||||
# msg = joint.name + 'is not set its lower limit. Please set it and try again.'
|
||||
# return msg
|
||||
# elif not max_enabled and min_enabled:
|
||||
# msg = joint.name + 'is not set its upper limit. Please set it and try again.'
|
||||
# return msg
|
||||
# else: # if there is no angle limit
|
||||
# joint_dict['type'] = 'continuous'
|
||||
|
||||
# elif joint_type == 'prismatic':
|
||||
# joint_dict['axis'] = [round(i, 6) for i in \
|
||||
# joint.jointMotion.slideDirectionVector.asArray()] # Also normalized
|
||||
# max_enabled = joint.jointMotion.slideLimits.isMaximumValueEnabled
|
||||
# min_enabled = joint.jointMotion.slideLimits.isMinimumValueEnabled
|
||||
# if max_enabled and min_enabled:
|
||||
# joint_dict['upper_limit'] = round(joint.jointMotion.slideLimits.maximumValue/100, 6)
|
||||
# joint_dict['lower_limit'] = round(joint.jointMotion.slideLimits.minimumValue/100, 6)
|
||||
# elif max_enabled and not min_enabled:
|
||||
# msg = joint.name + 'is not set its lower limit. Please set it and try again.'
|
||||
# return msg
|
||||
# elif not max_enabled and min_enabled:
|
||||
# msg = joint.name + 'is not set its upper limit. Please set it and try again.'
|
||||
# return msg
|
||||
# elif joint_type == 'fixed':
|
||||
# pass
|
||||
|
||||
# def get_parent(occ):
|
||||
# # function to find the root component of the joint. This is necessary for the correct component name in the urdf file
|
||||
# if occ.assemblyContext != None:
|
||||
# #print(occ.name)
|
||||
# occ = get_parent(occ.assemblyContext)
|
||||
# return occ
|
||||
|
||||
# if joint.occurrenceTwo != None and joint.occurrenceOne != None and joint.occurrenceOne.isLightBulbOn:
|
||||
# parent_occ = get_parent(joint.occurrenceTwo)
|
||||
# # print("Joint 1 Parent: " +parent_occ.name)
|
||||
# if "base_link" in parent_occ.name:
|
||||
# joint_dict['parent'] = 'base_link'
|
||||
# base_link = parent_occ
|
||||
# else:
|
||||
# joint_dict['parent'] = re.sub('[ :()]', '_', parent_occ.name)
|
||||
# # print("Joint 2: " +joint.occurrenceOne.name)
|
||||
# parent_occ = get_parent(joint.occurrenceOne)
|
||||
# # print("Joint 2 Parent: " +parent_occ.name)
|
||||
# joint_dict['child'] = re.sub('[ :()]', '_', parent_occ.name) <-- part of original
|
||||
# # joint_dict['child'] = utils.get_valid_filename(joint.occurrenceOne.fullPathName)
|
||||
|
||||
|
||||
# # if joint.occurrenceTwo.component.name == 'base_link':
|
||||
# # joint_dict['parent'] = 'base_link'
|
||||
# # else:
|
||||
# # joint_dict['parent'] = utils.get_valid_filename(joint.occurrenceTwo.fullPathName)
|
||||
# # joint_dict['child'] = utils.get_valid_filename(joint.occurrenceOne.fullPathName)
|
||||
|
||||
# ############### Auxiliary Function for the geometryOrOriginTwo issue
|
||||
# # The fix is from @syuntoku14/fusion2urdf, commited by @SpaceMaster85, https://github.com/syuntoku14/fusion2urdf/commit/8786e6318cdcaaf32070148451a27ab6e4f6697d
|
||||
|
||||
# #There seem to be a problem with geometryOrOriginTwo. To calcualte the correct orogin of the generated stl files following approach was used.
|
||||
# #https://forums.autodesk.com/t5/fusion-360-api-and-scripts/difference-of-geometryororiginone-and-geometryororiginonetwo/m-p/9837767
|
||||
# #Thanks to Masaki Yamamoto!
|
||||
|
||||
# # Coordinate transformation by matrix
|
||||
# # M: 4x4 transformation matrix
|
||||
# # a: 3D vector
|
||||
# def trans(M, a):
|
||||
# ex = [M[0],M[4],M[8]]
|
||||
# ey = [M[1],M[5],M[9]]
|
||||
# ez = [M[2],M[6],M[10]]
|
||||
# oo = [M[3],M[7],M[11]]
|
||||
# b = [0, 0, 0]
|
||||
# for i in range(3):
|
||||
# b[i] = a[0]*ex[i]+a[1]*ey[i]+a[2]*ez[i]+oo[i]
|
||||
# return(b)
|
||||
# # Returns True if two arrays are element-wise equal within a tolerance
|
||||
# def allclose(v1, v2, tol=1e-6):
|
||||
# return( max([abs(a-b) for a,b in zip(v1, v2)]) < tol )
|
||||
# ####################################
|
||||
|
||||
|
||||
# try:
|
||||
# ## A fix from @SpaceMaster85
|
||||
# xyz_from_one_to_joint = joint.geometryOrOriginOne.origin.asArray() # Relative Joint pos
|
||||
# xyz_from_two_to_joint = joint.geometryOrOriginTwo.origin.asArray() # Relative Joint pos
|
||||
# xyz_of_one = joint.occurrenceOne.transform.translation.asArray() # Link origin
|
||||
# xyz_of_two = joint.occurrenceTwo.transform.translation.asArray() # Link origin
|
||||
# M_two = joint.occurrenceTwo.transform.asArray() # Matrix as a 16 element array.
|
||||
|
||||
# # Compose joint position
|
||||
# case1 = allclose(xyz_from_two_to_joint, xyz_from_one_to_joint)
|
||||
# case2 = allclose(xyz_from_two_to_joint, xyz_of_one)
|
||||
# if case1 or case2:
|
||||
# xyz_of_joint = xyz_from_two_to_joint
|
||||
# else:
|
||||
# xyz_of_joint = trans(M_two, xyz_from_two_to_joint)
|
||||
|
||||
|
||||
# joint_dict['xyz'] = [round(i / 100.0, 6) for i in xyz_of_joint] # converted to meter
|
||||
# except:
|
||||
# try:
|
||||
# if type(joint.geometryOrOriginTwo)==adsk.fusion.JointOrigin:
|
||||
# data = joint.geometryOrOriginTwo.geometry.origin.asArray()
|
||||
# else:
|
||||
# data = joint.geometryOrOriginTwo.origin.asArray()
|
||||
# joint_dict['xyz'] = [round(i / 100.0, 6) for i in data] # converted to meter
|
||||
# except:
|
||||
# msg = joint.name + " doesn't have joint origin. Please set it and run again."
|
||||
# return msg
|
||||
|
||||
# # print("Processed joint {}, parent {}, child {}".format(joint.name, joint_dict['parent'], joint_dict['child']))
|
||||
# return joint_dict
|
181
Bullet_URDF_Exporter/core/Link.py
Normal file
|
@ -0,0 +1,181 @@
|
|||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Export Link infos to XML from Fusion 360
|
||||
|
||||
@syuntoku
|
||||
@yanshil
|
||||
"""
|
||||
|
||||
import adsk, re
|
||||
from xml.etree.ElementTree import Element, SubElement
|
||||
from ..utils import utils
|
||||
|
||||
class Link:
|
||||
|
||||
def __init__(self, name, xyz, center_of_mass, repo, mass, inertia_tensor):
|
||||
"""
|
||||
Parameters
|
||||
----------
|
||||
name: str
|
||||
name of the link
|
||||
xyz: [x, y, z]
|
||||
coordinate for the visual and collision
|
||||
center_of_mass: [x, y, z]
|
||||
coordinate for the center of mass
|
||||
link_xml: str
|
||||
generated xml describing about the link
|
||||
repo: str
|
||||
the name of the repository to save the xml file
|
||||
mass: float
|
||||
mass of the link
|
||||
inertia_tensor: [ixx, iyy, izz, ixy, iyz, ixz]
|
||||
tensor of the inertia
|
||||
"""
|
||||
self.name = name
|
||||
# xyz for visual
|
||||
self.xyz = [-_ for _ in xyz] # reverse the sign of xyz
|
||||
# xyz for center of mass
|
||||
self.center_of_mass = center_of_mass
|
||||
self.link_xml = None
|
||||
self.repo = repo
|
||||
self.mass = mass
|
||||
self.inertia_tensor = inertia_tensor
|
||||
|
||||
def make_link_xml(self):
|
||||
"""
|
||||
Generate the link_xml and hold it by self.link_xml
|
||||
"""
|
||||
|
||||
link = Element('link')
|
||||
link.attrib = {'name':self.name}
|
||||
|
||||
#inertial
|
||||
inertial = SubElement(link, 'inertial')
|
||||
origin_i = SubElement(inertial, 'origin')
|
||||
origin_i.attrib = {'xyz':' '.join([str(_) for _ in self.center_of_mass]), 'rpy':'0 0 0'}
|
||||
mass = SubElement(inertial, 'mass')
|
||||
mass.attrib = {'value':str(self.mass)}
|
||||
inertia = SubElement(inertial, 'inertia')
|
||||
inertia.attrib = \
|
||||
{'ixx':str(self.inertia_tensor[0]), 'iyy':str(self.inertia_tensor[1]),\
|
||||
'izz':str(self.inertia_tensor[2]), 'ixy':str(self.inertia_tensor[3]),\
|
||||
'iyz':str(self.inertia_tensor[4]), 'ixz':str(self.inertia_tensor[5])}
|
||||
|
||||
# visual
|
||||
visual = SubElement(link, 'visual')
|
||||
origin_v = SubElement(visual, 'origin')
|
||||
origin_v.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
geometry_v = SubElement(visual, 'geometry')
|
||||
mesh_v = SubElement(geometry_v, 'mesh')
|
||||
mesh_v.attrib = {'filename': self.repo + self.name + '.stl','scale':'0.001 0.001 0.001'} ## scale = 0.001 means mm to m. Modify it according if using another unit
|
||||
material = SubElement(visual, 'material')
|
||||
material.attrib = {'name':'silver'}
|
||||
|
||||
# collision
|
||||
collision = SubElement(link, 'collision')
|
||||
origin_c = SubElement(collision, 'origin')
|
||||
origin_c.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
geometry_c = SubElement(collision, 'geometry')
|
||||
mesh_c = SubElement(geometry_c, 'mesh')
|
||||
mesh_c.attrib = {'filename': self.repo + self.name + '.stl','scale':'0.001 0.001 0.001'} ## scale = 0.001 means mm to m. Modify it according if using another unit
|
||||
material = SubElement(visual, 'material')
|
||||
|
||||
# print("\n".join(utils.prettify(link).split("\n")[1:]))
|
||||
self.link_xml = "\n".join(utils.prettify(link).split("\n")[1:])
|
||||
|
||||
def make_inertial_dict(root, msg):
|
||||
"""
|
||||
Parameters
|
||||
----------
|
||||
root: adsk.fusion.Design.cast(product)
|
||||
Root component
|
||||
msg: str
|
||||
Tell the status
|
||||
|
||||
Returns
|
||||
----------
|
||||
inertial_dict: {name:{mass, inertia, center_of_mass}}
|
||||
|
||||
msg: str
|
||||
Tell the status
|
||||
"""
|
||||
# Get component properties.
|
||||
allOccs = root.occurrences
|
||||
inertial_dict = {}
|
||||
|
||||
for occs in allOccs:
|
||||
# Skip the root component.
|
||||
occs_dict = {}
|
||||
prop = occs.getPhysicalProperties(adsk.fusion.CalculationAccuracy.VeryHighCalculationAccuracy)
|
||||
|
||||
occs_dict['name'] = re.sub('[ :()]', '_', occs.name)
|
||||
|
||||
mass = prop.mass # kg
|
||||
occs_dict['mass'] = mass
|
||||
center_of_mass = [_/100.0 for _ in prop.centerOfMass.asArray()] ## cm to m
|
||||
occs_dict['center_of_mass'] = center_of_mass
|
||||
|
||||
# https://help.autodesk.com/view/fusion360/ENU/?guid=GUID-ce341ee6-4490-11e5-b25b-f8b156d7cd97
|
||||
(_, xx, yy, zz, xy, yz, xz) = prop.getXYZMomentsOfInertia()
|
||||
moment_inertia_world = [_ / 10000.0 for _ in [xx, yy, zz, xy, yz, xz] ] ## kg / cm^2 -> kg/m^2
|
||||
occs_dict['inertia'] = utils.origin2center_of_mass(moment_inertia_world, center_of_mass, mass)
|
||||
|
||||
if 'base_link' in occs.component.name:
|
||||
inertial_dict['base_link'] = occs_dict
|
||||
else:
|
||||
inertial_dict[re.sub('[ :()]', '_', occs.name)] = occs_dict
|
||||
|
||||
return inertial_dict, msg
|
||||
# def make_inertial_dict(root, msg):
|
||||
# """
|
||||
# Parameters
|
||||
# ----------
|
||||
# root: adsk.fusion.Design.cast(product)
|
||||
# Root component
|
||||
# msg: str
|
||||
# Tell the status
|
||||
|
||||
# Returns
|
||||
# ----------
|
||||
# inertial_dict: {name:{mass, inertia, center_of_mass}}
|
||||
|
||||
# msg: str
|
||||
# Tell the status
|
||||
# """
|
||||
# # Get ALL component properties.
|
||||
# allOccs = root.allOccurrences
|
||||
# inertial_dict = {}
|
||||
|
||||
# for occs in allOccs:
|
||||
# # Skip the root component.
|
||||
# occs_dict = {}
|
||||
# prop = occs.getPhysicalProperties(adsk.fusion.CalculationAccuracy.VeryHighCalculationAccuracy)
|
||||
|
||||
|
||||
|
||||
# mass = prop.mass # kg
|
||||
# occs_dict['mass'] = mass
|
||||
# center_of_mass = [_/100.0 for _ in prop.centerOfMass.asArray()] ## cm to m
|
||||
# occs_dict['center_of_mass'] = center_of_mass
|
||||
|
||||
# # https://help.autodesk.com/view/fusion360/ENU/?guid=GUID-ce341ee6-4490-11e5-b25b-f8b156d7cd97
|
||||
# (_, xx, yy, zz, xy, yz, xz) = prop.getXYZMomentsOfInertia()
|
||||
# moment_inertia_world = [_ / 10000.0 for _ in [xx, yy, zz, xy, yz, xz] ] ## kg / cm^2 -> kg/m^2
|
||||
# occs_dict['inertia'] = utils.origin2center_of_mass(moment_inertia_world, center_of_mass, mass)
|
||||
|
||||
# # if occs.component.name == 'base_link':
|
||||
# # occs_dict['name'] = 'base_link'
|
||||
# # inertial_dict['base_link'] = occs_dict
|
||||
# # # print("Processing Base Link")
|
||||
|
||||
# if 'base_link' in occs.component.name:
|
||||
# inertial_dict['base_link'] = occs_dict
|
||||
# else:
|
||||
# # occs_dict['name'] = re.sub('[ :()]', '_', occs.name)
|
||||
# key = utils.get_valid_filename(occs.fullPathName)
|
||||
# occs_dict['name'] = key
|
||||
# inertial_dict[key] = occs_dict
|
||||
|
||||
# # print("Exporting link {}".format(occs_dict['name']))
|
||||
|
||||
# return inertial_dict, msg
|
177
Bullet_URDF_Exporter/core/Write.py
Normal file
|
@ -0,0 +1,177 @@
|
|||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Created on Sun May 12 20:46:26 2019
|
||||
|
||||
@author: syuntoku
|
||||
"""
|
||||
|
||||
import adsk, os, re
|
||||
from xml.etree.ElementTree import Element, SubElement
|
||||
from . import Link, Joint
|
||||
from ..utils import utils
|
||||
|
||||
def write_link_urdf(joints_dict, repo, links_xyz_dict, file_name, inertial_dict):
|
||||
"""
|
||||
Write links information into urdf "repo/file_name"
|
||||
|
||||
|
||||
Parameters
|
||||
----------
|
||||
joints_dict: dict
|
||||
information of the each joint
|
||||
repo: str
|
||||
the name of the repository to save the xml file
|
||||
links_xyz_dict: vacant dict
|
||||
xyz information of the each link
|
||||
file_name: str
|
||||
urdf full path
|
||||
inertial_dict:
|
||||
information of the each inertial
|
||||
|
||||
Note
|
||||
----------
|
||||
In this function, links_xyz_dict is set for write_joint_tran_urdf.
|
||||
The origin of the coordinate of center_of_mass is the coordinate of the link
|
||||
"""
|
||||
with open(file_name, mode='a') as f:
|
||||
# for base_link
|
||||
center_of_mass = inertial_dict['base_link']['center_of_mass']
|
||||
link = Link.Link(name='base_link', xyz=[0,0,0],
|
||||
center_of_mass=center_of_mass, repo=repo,
|
||||
mass=inertial_dict['base_link']['mass'],
|
||||
inertia_tensor=inertial_dict['base_link']['inertia'])
|
||||
links_xyz_dict[link.name] = link.xyz
|
||||
link.make_link_xml()
|
||||
f.write(link.link_xml)
|
||||
f.write('\n')
|
||||
|
||||
# others
|
||||
for joint in joints_dict:
|
||||
num_child = 0
|
||||
for joint_search in joints_dict:
|
||||
if joints_dict[joint]['child'] == joints_dict[joint_search]['child']:
|
||||
num_child += 1
|
||||
|
||||
if num_child > 1:
|
||||
app = adsk.core.Application.get()
|
||||
ui = app.userInterface
|
||||
ui.messageBox("Component %s with more than one child connection.\
|
||||
\nThis mostly happens when you connect several subcomponents to different parents.\
|
||||
\nBe aware to threat nested componets as a singel component!"
|
||||
% (joints_dict[joint]['child']), "Error!")
|
||||
quit()
|
||||
else:
|
||||
name = re.sub('[ :()]', '_', joints_dict[joint]['child'])
|
||||
center_of_mass = \
|
||||
[ i-j for i, j in zip(inertial_dict[name]['center_of_mass'], joints_dict[joint]['xyz'])]
|
||||
link = Link.Link(name=name, xyz=joints_dict[joint]['xyz'],\
|
||||
center_of_mass=center_of_mass,\
|
||||
repo=repo, mass=inertial_dict[name]['mass'],\
|
||||
inertia_tensor=inertial_dict[name]['inertia'])
|
||||
links_xyz_dict[link.name] = link.xyz
|
||||
link.make_link_xml()
|
||||
f.write(link.link_xml)
|
||||
f.write('\n')
|
||||
|
||||
|
||||
def write_joint_tran_urdf(joints_dict, repo, links_xyz_dict, file_name):
|
||||
"""
|
||||
Write joints and transmission information into urdf "repo/file_name"
|
||||
|
||||
|
||||
Parameters
|
||||
----------
|
||||
joints_dict: dict
|
||||
information of the each joint
|
||||
repo: str
|
||||
the name of the repository to save the xml file
|
||||
links_xyz_dict: dict
|
||||
xyz information of the each link
|
||||
file_name: str
|
||||
urdf full path
|
||||
"""
|
||||
|
||||
with open(file_name, mode='a') as f:
|
||||
for j in joints_dict:
|
||||
parent = joints_dict[j]['parent']
|
||||
child = joints_dict[j]['child']
|
||||
joint_type = joints_dict[j]['type']
|
||||
upper_limit = joints_dict[j]['upper_limit']
|
||||
lower_limit = joints_dict[j]['lower_limit']
|
||||
try:
|
||||
xyz = [round(p-c, 6) for p, c in \
|
||||
zip(links_xyz_dict[parent], links_xyz_dict[child])] # xyz = parent - child
|
||||
except KeyError as ke:
|
||||
app = adsk.core.Application.get()
|
||||
ui = app.userInterface
|
||||
ui.messageBox("Joint %s: There seems to be an error with the connection between\n\n%s\nand\n%s\n\nCheck \
|
||||
whether the connections\nparent=component2=%s\nchild=component1=%s\nare correct or if you need \
|
||||
to swap component1<=>component2"
|
||||
% (j, parent, child, parent, child), "Error!")
|
||||
quit()
|
||||
|
||||
joint = Joint.Joint(name=j, joint_type = joint_type, xyz=xyz, \
|
||||
axis=joints_dict[j]['axis'], parent=parent, child=child, \
|
||||
upper_limit=upper_limit, lower_limit=lower_limit)
|
||||
joint.make_joint_xml()
|
||||
joint.make_transmission_xml()
|
||||
f.write(joint.joint_xml)
|
||||
if joint_type != 'fixed':
|
||||
f.write(joint.tran_xml)
|
||||
f.write('\n')
|
||||
|
||||
|
||||
def write_urdf(joints_dict, links_xyz_dict, inertial_dict, package_name, save_dir, robot_name):
|
||||
file_name = save_dir + '/' + robot_name + '.urdf' # the name of urdf file
|
||||
repo = 'meshes/' # Pybullet only need relative paths
|
||||
with open(file_name, mode='w') as f:
|
||||
f.write('<?xml version="1.0" ?>\n')
|
||||
f.write('<robot name="{}">\n'.format(robot_name))
|
||||
f.write('\n')
|
||||
f.write('<material name="silver">\n')
|
||||
f.write(' <color rgba="0.700 0.700 0.700 1.000"/>\n')
|
||||
f.write('</material>\n')
|
||||
f.write('\n')
|
||||
|
||||
write_link_urdf(joints_dict, repo, links_xyz_dict, file_name, inertial_dict)
|
||||
write_joint_tran_urdf(joints_dict, repo, links_xyz_dict, file_name)
|
||||
write_endtag(file_name)
|
||||
|
||||
def write_endtag(file_name):
|
||||
"""
|
||||
Write the </robot> tag at the end of the urdf
|
||||
Parameters
|
||||
----------
|
||||
file_name: str
|
||||
urdf full path
|
||||
"""
|
||||
with open(file_name, mode='a') as f:
|
||||
f.write('</robot>\n')
|
||||
|
||||
def write_hello_pybullet(robot_name, save_dir):
|
||||
robot_urdf = robot_name + '.urdf' ## basename of robot.urdf
|
||||
file_name = save_dir + '/' + 'hello_bullet.py'
|
||||
hello_pybullet = """import pybullet as p
|
||||
import time
|
||||
import pybullet_data
|
||||
physicsClient = p.connect(p.GUI)#or p.DIRECT for non-graphical version
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath()) #optionally
|
||||
p.setGravity(0,0,-10)
|
||||
planeId = p.loadURDF("plane.urdf")
|
||||
cubeStartPos = [0,0,0]
|
||||
cubeStartOrientation = p.getQuaternionFromEuler([0,0,0])
|
||||
robotId = p.loadURDF("TEMPLATE.urdf",cubeStartPos, cubeStartOrientation,
|
||||
# useMaximalCoordinates=1, ## New feature in Pybullet
|
||||
flags=p.URDF_USE_INERTIA_FROM_FILE)
|
||||
for i in range (10000):
|
||||
p.stepSimulation()
|
||||
time.sleep(1./240.)
|
||||
cubePos, cubeOrn = p.getBasePositionAndOrientation(robotId)
|
||||
print(cubePos,cubeOrn)
|
||||
p.disconnect()
|
||||
"""
|
||||
hello_pybullet = hello_pybullet.replace('TEMPLATE.urdf', robot_urdf).replace('\t', ' ')
|
||||
with open(file_name, mode='w') as f:
|
||||
f.write(hello_pybullet)
|
||||
f.write('\n')
|
||||
|
0
Bullet_URDF_Exporter/core/__init__.py
Normal file
0
Bullet_URDF_Exporter/utils/__init__.py
Normal file
260
Bullet_URDF_Exporter/utils/utils.py
Normal file
|
@ -0,0 +1,260 @@
|
|||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Copy to new components and export stls.
|
||||
|
||||
@syuntoku
|
||||
@yanshil
|
||||
"""
|
||||
|
||||
import adsk, adsk.core, adsk.fusion
|
||||
import os.path, re
|
||||
from xml.etree import ElementTree
|
||||
from xml.dom import minidom
|
||||
|
||||
def export_stl(_app, save_dir):
|
||||
"""
|
||||
export stl files into "sace_dir/"
|
||||
|
||||
|
||||
Parameters
|
||||
----------
|
||||
_app: adsk.core.Application.get()
|
||||
save_dir: str
|
||||
directory path to save
|
||||
"""
|
||||
|
||||
def traverse( occ):
|
||||
# recursive method to get all bodies from components and sub-components
|
||||
body = adsk.fusion.BRepBody.cast(None)
|
||||
liste = []
|
||||
if occ.childOccurrences and occ.isLightBulbOn:
|
||||
for child in occ.childOccurrences:
|
||||
liste = liste + traverse(child)
|
||||
if occ.isLightBulbOn:
|
||||
liste = liste + [body for body in occ.bRepBodies if body.isLightBulbOn and occ.component.isBodiesFolderLightBulbOn]
|
||||
return liste
|
||||
|
||||
|
||||
des: adsk.fusion.Design = _app.activeProduct
|
||||
root: adsk.fusion.Component = des.rootComponent
|
||||
|
||||
showBodies = []
|
||||
body = adsk.fusion.BRepBody.cast(None)
|
||||
if root.isBodiesFolderLightBulbOn:
|
||||
lst = [body for body in root.bRepBodies if body.isLightBulbOn]
|
||||
if len(lst) > 0:
|
||||
showBodies.append(['root', lst])
|
||||
|
||||
occ = adsk.fusion.Occurrence.cast(None)
|
||||
for occ in root.allOccurrences:
|
||||
if not occ.assemblyContext and occ.isLightBulbOn:
|
||||
lst = [body for body in occ.bRepBodies if body.isLightBulbOn and occ.component.isBodiesFolderLightBulbOn]
|
||||
if occ.childOccurrences:
|
||||
for child in occ.childOccurrences:
|
||||
lst = lst + traverse(child)
|
||||
if len(lst) > 0:
|
||||
showBodies.append([occ.name, lst])
|
||||
|
||||
# get clone body
|
||||
tmpBrepMng = adsk.fusion.TemporaryBRepManager.get()
|
||||
tmpBodies = []
|
||||
for name, bodies in showBodies:
|
||||
lst = [tmpBrepMng.copy(body) for body in bodies]
|
||||
if len(lst) > 0:
|
||||
tmpBodies.append([name, lst])
|
||||
|
||||
# create export Doc - DirectDesign
|
||||
fusionDocType = adsk.core.DocumentTypes.FusionDesignDocumentType
|
||||
expDoc: adsk.fusion.FusionDocument = _app.documents.add(fusionDocType)
|
||||
expDes: adsk.fusion.Design = expDoc.design
|
||||
expDes.designType = adsk.fusion.DesignTypes.DirectDesignType
|
||||
|
||||
# get export rootComponent
|
||||
expRoot: adsk.fusion.Component = expDes.rootComponent
|
||||
|
||||
# paste clone body
|
||||
mat0 = adsk.core.Matrix3D.create()
|
||||
for name, bodies in tmpBodies:
|
||||
occ = expRoot.occurrences.addNewComponent(mat0)
|
||||
comp = occ.component
|
||||
comp.name = name
|
||||
for body in bodies:
|
||||
comp.bRepBodies.add(body)
|
||||
|
||||
# export stl
|
||||
try:
|
||||
os.mkdir(save_dir + '/meshes')
|
||||
except:
|
||||
pass
|
||||
exportFolder = save_dir + '/meshes'
|
||||
|
||||
exportMgr = des.exportManager
|
||||
for occ in expRoot.allOccurrences:
|
||||
if "base_link" in occ.component.name:
|
||||
expName = "base_link"
|
||||
else:
|
||||
expName = re.sub('[ :()]', '_', occ.component.name)
|
||||
expPath = os.path.join(exportFolder, '{}.stl'.format(expName))
|
||||
stlOpts = exportMgr.createSTLExportOptions(occ, expPath)
|
||||
exportMgr.execute(stlOpts)
|
||||
|
||||
# remove export Doc
|
||||
expDoc.close(False)
|
||||
|
||||
## https://github.com/django/django/blob/master/django/utils/text.py
|
||||
def get_valid_filename(s):
|
||||
"""
|
||||
Return the given string converted to a string that can be used for a clean
|
||||
filename. Remove leading and trailing spaces; convert other spaces to
|
||||
underscores; and remove anything that is not an alphanumeric, dash,
|
||||
underscore, or dot.
|
||||
>>> get_valid_filename("john's portrait in 2004.jpg")
|
||||
'johns_portrait_in_2004.jpg'
|
||||
"""
|
||||
s = str(s).strip().replace(' ', '_')
|
||||
return re.sub(r'(?u)[^-\w.]', '', s)
|
||||
|
||||
|
||||
def copy_occs(root):
|
||||
"""
|
||||
duplicate all the components
|
||||
"""
|
||||
def copy_body(allOccs, occs):
|
||||
"""
|
||||
copy the old occs to new component
|
||||
"""
|
||||
|
||||
bodies = occs.bRepBodies
|
||||
transform = adsk.core.Matrix3D.create()
|
||||
|
||||
# Create new components from occs
|
||||
# This support even when a component has some occses.
|
||||
|
||||
new_occs = allOccs.addNewComponent(transform) # this create new occs
|
||||
if occs.component.name == 'base_link':
|
||||
occs.component.name = 'old_component'
|
||||
new_occs.component.name = 'base_link'
|
||||
else:
|
||||
key = get_valid_filename(occs.fullPathName)
|
||||
new_occs.component.name = key
|
||||
# new_occs.component.name = re.sub('[ :()]', '_', occs.name)
|
||||
new_occs = allOccs.item((allOccs.count-1))
|
||||
for i in range(bodies.count):
|
||||
body = bodies.item(i)
|
||||
body.copyToComponent(new_occs)
|
||||
|
||||
allOccs = root.occurrences
|
||||
# allOccs = root.allOccurrences
|
||||
|
||||
oldOccs = []
|
||||
# coppy_list = [occs for occs in allOccs]
|
||||
coppy_list = [occs for occs in root.allOccurrences]
|
||||
for occs in coppy_list:
|
||||
if occs.bRepBodies.count > 0:
|
||||
copy_body(allOccs, occs)
|
||||
oldOccs.append(occs)
|
||||
|
||||
for occs in oldOccs:
|
||||
occs.component.name = 'old_component'
|
||||
|
||||
|
||||
# def export_stl(design, save_dir, components):
|
||||
# """
|
||||
# export stl files into "sace_dir/"
|
||||
|
||||
|
||||
# Parameters
|
||||
# ----------
|
||||
# design: adsk.fusion.Design.cast(product)
|
||||
# save_dir: str
|
||||
# directory path to save
|
||||
# components: design.allComponents
|
||||
# """
|
||||
|
||||
# # create a single exportManager instance
|
||||
# exportMgr = design.exportManager
|
||||
# # get the script location
|
||||
# try: os.mkdir(save_dir + '/meshes')
|
||||
# except: pass
|
||||
# scriptDir = save_dir + '/meshes'
|
||||
# # export the occurrence one by one in the component to a specified file
|
||||
# for component in components:
|
||||
# allOccus = component.allOccurrences
|
||||
# for occ in allOccus:
|
||||
# ## Don't export nested component
|
||||
# if occ.childOccurrences.count > 0:
|
||||
# continue
|
||||
|
||||
# if 'old_component' not in occ.component.name:
|
||||
# try:
|
||||
# key = get_valid_filename(occ.fullPathName)
|
||||
# key = key[:-1] ## Will generate an extra "1" in the end, remove it
|
||||
# print("Export file: {}".format(key))
|
||||
# # fileName = scriptDir + "/" + occ.component.name
|
||||
# fileName = scriptDir + "/" + key
|
||||
# # create stl exportOptions
|
||||
# stlExportOptions = exportMgr.createSTLExportOptions(occ, fileName)
|
||||
# stlExportOptions.sendToPrintUtility = False
|
||||
# stlExportOptions.isBinaryFormat = True
|
||||
# # options are .MeshRefinementLow .MeshRefinementMedium .MeshRefinementHigh
|
||||
# stlExportOptions.meshRefinement = adsk.fusion.MeshRefinementSettings.MeshRefinementLow
|
||||
# exportMgr.execute(stlExportOptions)
|
||||
# except:
|
||||
# print('Component ' + occ.component.name + ' has something wrong.')
|
||||
|
||||
|
||||
def file_dialog(ui):
|
||||
"""
|
||||
display the dialog to save the file
|
||||
"""
|
||||
# Set styles of folder dialog.
|
||||
folderDlg = ui.createFolderDialog()
|
||||
folderDlg.title = 'Fusion Folder Dialog'
|
||||
|
||||
# Show folder dialog
|
||||
dlgResult = folderDlg.showDialog()
|
||||
if dlgResult == adsk.core.DialogResults.DialogOK:
|
||||
return folderDlg.folder
|
||||
return False
|
||||
|
||||
|
||||
def origin2center_of_mass(inertia, center_of_mass, mass):
|
||||
"""
|
||||
convert the moment of the inertia about the world coordinate into
|
||||
that about center of mass coordinate
|
||||
|
||||
|
||||
Parameters
|
||||
----------
|
||||
moment of inertia about the world coordinate: [xx, yy, zz, xy, yz, xz]
|
||||
center_of_mass: [x, y, z]
|
||||
|
||||
|
||||
Returns
|
||||
----------
|
||||
moment of inertia about center of mass : [xx, yy, zz, xy, yz, xz]
|
||||
"""
|
||||
x = center_of_mass[0]
|
||||
y = center_of_mass[1]
|
||||
z = center_of_mass[2]
|
||||
translation_matrix = [y**2+z**2, x**2+z**2, x**2+y**2,
|
||||
-x*y, -y*z, -x*z]
|
||||
return [ i - mass*t for i, t in zip(inertia, translation_matrix)]
|
||||
|
||||
|
||||
def prettify(elem):
|
||||
"""
|
||||
Return a pretty-printed XML string for the Element.
|
||||
Parameters
|
||||
----------
|
||||
elem : xml.etree.ElementTree.Element
|
||||
|
||||
|
||||
Returns
|
||||
----------
|
||||
pretified xml : str
|
||||
"""
|
||||
rough_string = ElementTree.tostring(elem, 'utf-8')
|
||||
reparsed = minidom.parseString(rough_string)
|
||||
return reparsed.toprettyxml(indent=" ")
|
||||
|
21
LICENSE
Normal file
|
@ -0,0 +1,21 @@
|
|||
MIT License
|
||||
|
||||
Copyright (c) 2018 Toshinori Kitamura
|
||||
|
||||
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
of this software and associated documentation files (the "Software"), to deal
|
||||
in the Software without restriction, including without limitation the rights
|
||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
copies of the Software, and to permit persons to whom the Software is
|
||||
furnished to do so, subject to the following conditions:
|
||||
|
||||
The above copyright notice and this permission notice shall be included in all
|
||||
copies or substantial portions of the Software.
|
||||
|
||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
SOFTWARE.
|
131
README.md
Normal file
|
@ -0,0 +1,131 @@
|
|||
# Fusion2Pybullet
|
||||
|
||||
[简体中文](README.zh.md) | English
|
||||
|
||||
Developed from [@syuntoku14/fusion2urdf](https://github.com/syuntoku14/fusion2urdf).
|
||||
|
||||
### What is this script?
|
||||
|
||||
A Fusion 360 script to export urdf files. This is a PyBullet adpative version.
|
||||
|
||||
Note: Only support "Revolute", "Rigid" and "Slider" joint currently. Also I don't have plans to work on rigid group and other types of joints.
|
||||
|
||||
This exports:
|
||||
|
||||
* .urdf files of the model
|
||||
* .stl files of your model
|
||||
* A example hello.py to load your model into PyBullet.
|
||||
|
||||
---
|
||||
|
||||
03/03/2021: Pull the fix for xyz calculation from 01/09/2021 commit `d2e754086f092ac81c481a0c3862e3cecb1f4dfe` in [syuntoku14/fusion2urdf](https://github.com/syuntoku14/fusion2urdf/commit/d2e754086f092ac81c481a0c3862e3cecb1f4dfe)
|
||||
|
||||
- If you see that your components move arround the map center in rviz try this update
|
||||
- More Infos see [this link](https://forums.autodesk.com/t5/fusion-360-api-and-scripts/difference-of-geometryororiginone-and-geometryororiginonetwo/m-p/9837767)
|
||||
|
||||
03/27/2020 update2: Add a supplementary script **Joint2Graphviz** to check assembled structures.
|
||||
|
||||
03/27/2020 update: Add "Do not Capture Design History" to fix InternalValidationError. See [Developer Notes](https://github.com/yanshil/Fusion2Pyblluet/wiki/Developer-Notes)
|
||||
|
||||
**03/25/2020: Supporting exportation of nested components.**
|
||||
|
||||
|
||||
### Fusion Add-in
|
||||
Add this script into Fusion 360 via Tools -> Add-Ins
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
#### Before using this script
|
||||
|
||||
1. Some other notes for getting avoid of warnings:
|
||||
1. Change language preference to English
|
||||
2. Rename any full-width symbol to half-width symbol (like `。` and `()`)
|
||||
2. Set up `base_link`
|
||||
3. Suggestion: Use [**Joint2Graphviz**](https://github.com/yanshil/Joint2Graphviz) to check your assembled structure!
|
||||
4. **Check if your default unit is mm or not. If you set it to some other unit, you need to manually adjust the scale when exporting the stl fils. [See FAQ](#faq)**
|
||||
|
||||
#### Using script inside Fusion 360: Example
|
||||
|
||||
1. Set up the components properly
|
||||
|
||||
- [x] Unit should be mm (See [FAQ](#what-if-my-unit-is-not-mm) if it's not)
|
||||
|
||||
- [x] A base_link
|
||||
|
||||
- [x] Your file should not conatin extra file link. If any, right click on the component, do 'Break Link'
|
||||
- [x] File links will be generated when you do something like 'Insert into current design'
|
||||
- [x] So please make sure you did had a backup when you do the 'Break link' operations.
|
||||
|
||||
- [x] Check component and joint names (Set English as the language if necessary)
|
||||
|
||||
- [x] **IMPORTANT! Set up joints properly**
|
||||
|
||||
* Supplementary script: **Joint2Graphviz** will generate a txt file capable for Graphviz. Copy the content to [WebGraphviz](http://www.webgraphviz.com/) to check the graph. Usually a correct model should be a DAG with 'base_link' as the only root.
|
||||
|
||||
* In fusion, when you hit 'J' to assemble joints, note that the exporter consider **component 1 as 'child' and component 2 as 'parent'**. For example, when you want to assemble a 4-wheel car with middle cuboid as `base_link`, you should assemble the vehicle with wheel as component 1 and 'base_link' as component 2.
|
||||
|
||||
* For example, you should be assemble your model to make result of `check_urdf simple_car.urdf` like the following. i.e. BL, BR, FL, FR as component 1 and base_link as component 2 when you assemble these 4 joints.
|
||||
```
|
||||
robot name is: simple_car
|
||||
---------- Successfully Parsed XML ---------------
|
||||
root Link: base_link has 4 child(ren)
|
||||
child(1): BL_1
|
||||
child(2): BR_1
|
||||
child(3): FL_1
|
||||
child(4): FR_1
|
||||
```
|
||||
|
||||
2. Run the script and select storing location
|
||||
* Note: **Don't save** your file after running the scripts! DesignType will be set to "Direct Mode" and some temporary components will be created. That's not the changes you want!
|
||||
* 
|
||||
* 
|
||||
* 
|
||||
|
||||
3. Enjoy from `python hello_bullet.py` !
|
||||
|
||||
## FAQ
|
||||
|
||||
### What to do when error pops out
|
||||
|
||||
* Bugs are usually caused by wrongly set up joints relationships
|
||||
* Nest-component support might also lead to undocumented bugs. So remove the nesting structure helps a lot.
|
||||
|
||||
Since the script still cannot showing warnings and errors elegantly, if you cannot figure out what went wrong with the model while bugs are usually caused by wrongly set up joints relationships, you can do the following things:
|
||||
|
||||
1. Make sure every joints are set up correct (parent and child relationship). If failed --->
|
||||
2. Re-tidy your design to make it not include any nest-components. Use this script. If failed --->
|
||||
3. Try the stable version [Branch: stable](https://github.com/yanshil/Fusion2Pyblluet/tree/stable).
|
||||
4. Run with debug mode and check what happens 
|
||||
|
||||
### How to check if I assembled my links and joints correctly
|
||||
|
||||
A supporting script here: [Joint2Graphviz](https://github.com/yanshil/Joint2Graphviz) for details
|
||||
|
||||
### What if my unit is not mm
|
||||
|
||||
You have to modify `Bullet_URDF_Exporter/core/Link.py`. Search `scale`
|
||||
|
||||
(Please ping me if you find any other place that should also be modified)
|
||||
|
||||
```
|
||||
# visual
|
||||
visual = SubElement(link, 'visual')
|
||||
origin_v = SubElement(visual, 'origin')
|
||||
origin_v.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
geometry_v = SubElement(visual, 'geometry')
|
||||
mesh_v = SubElement(geometry_v, 'mesh')
|
||||
mesh_v.attrib = {'filename': self.repo + self.name + '.stl','scale':'0.001 0.001 0.001'} ## scale = 0.001 means mm to m. Modify it according if using another unit
|
||||
material = SubElement(visual, 'material')
|
||||
material.attrib = {'name':'silver'}
|
||||
|
||||
# collision
|
||||
collision = SubElement(link, 'collision')
|
||||
origin_c = SubElement(collision, 'origin')
|
||||
origin_c.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
geometry_c = SubElement(collision, 'geometry')
|
||||
mesh_c = SubElement(geometry_c, 'mesh')
|
||||
mesh_c.attrib = {'filename': self.repo + self.name + '.stl','scale':'0.001 0.001 0.001'} ## scale = 0.001 means mm to m. Modify it according if using another unit
|
||||
material = SubElement(visual, 'material')
|
||||
```
|
129
README.zh.md
Normal file
|
@ -0,0 +1,129 @@
|
|||
# Fusion2Pybullet
|
||||
|
||||
简体中文 | [English](README.md)
|
||||
|
||||
基于 [@syuntoku14/fusion2urdf](https://github.com/syuntoku14/fusion2urdf) 开发
|
||||
|
||||
### 这个脚本是干什么的?
|
||||
|
||||
这是一个专门用导出可用于从PyBullet的urdf文件的Fusion 360脚本。
|
||||
|
||||
P.S. 当前仅支持基本的“旋转”,“刚性”和“滑块”关节。并且我不打算继续加入刚性组和其他类型的关节的支持。
|
||||
|
||||
这个脚本会导出
|
||||
|
||||
* 模型的.urdf 文件
|
||||
* 相关的.stl 文件
|
||||
* 一个Python示例 hello.py, 用于将模型加载到PyBullet中
|
||||
|
||||
---
|
||||
|
||||
03/03/2021: 同步原 repo 的 xyz 计算方式 commit `d2e754086f092ac81c481a0c3862e3cecb1f4dfe` in [syuntoku14/fusion2urdf](https://github.com/syuntoku14/fusion2urdf/commit/d2e754086f092ac81c481a0c3862e3cecb1f4dfe)
|
||||
|
||||
- 如果你的模型有旋转轴错位的问题请尝试一下这个新版本
|
||||
- 问题详见 [于此](https://forums.autodesk.com/t5/fusion-360-api-and-scripts/difference-of-geometryororiginone-and-geometryororiginonetwo/m-p/9837767)
|
||||
|
||||
03/27/2020 更新2: 补充了一个脚本 **Joint2Graphviz** 用以检查模型结构。(用法:先运行Joing2Graphviz并查看关节结构,确认无误后再运行此脚本)
|
||||
|
||||
03/27/2020 更新1: 加入“不捕获设计历史记录”,这可以修复一部分的导出问题。 参见 [Developer Notes](https://github.com/yanshil/Fusion2Pyblluet/wiki/Developer-Notes)
|
||||
|
||||
**03/25/2020: 支持嵌套组件的导出(原repo并不支持此项)**
|
||||
|
||||
|
||||
### Fusion Add-in
|
||||
通过工具->插件将此脚本添加到Fusion 360中
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
#### 使用此脚本之前
|
||||
|
||||
1. 其他一些避免Error的注意事项:
|
||||
1. 将Fusion360语言首选项更改为英语 (从而默认关节名改为英文单词)
|
||||
2. 将任何全角符号重命名为半角符号 (比如 `。` and `()`)
|
||||
2. 设置好`base_link`
|
||||
3. 一个重要建议: 先运行 [**Joint2Graphviz**](https://github.com/yanshil/Joint2Graphviz) 来检查一遍组装的结构!
|
||||
4. 检查一下单位是否为mm。如果你设置的是其他单位,那在导出stl fils时需要手动调整一下scale. [看看FAQ](#faq)
|
||||
|
||||
#### 举个栗子 Fusion 360:
|
||||
|
||||
1. 检查下列事项
|
||||
|
||||
- [x] 单位得是mm
|
||||
|
||||
- [x] 有一个 base_link (这个一般就是模型的root_node)
|
||||
|
||||
- [x] 用于导出的文件若有外部文件链接会产生问题。所以你需要对所有的外部链接部件进行“右键-断开链接”的操作。一定要记得先存档哦!
|
||||
|
||||
- [x] 检查零部件和联结名称 (语言首选项改回英语)
|
||||
|
||||
- [x] **重要!联结一定得设置正确!不然会有各种奇怪的错误跳出来。。。**
|
||||
|
||||
* 另一个脚本就是干这个的: **[Joint2Graphviz](https://github.com/yanshil/Joint2Graphviz) ** 将生成可用于Graphviz的txt文件. 将生成的txt的内容复制到 [WebGraphviz](http://www.webgraphviz.com/) 可以生成相应的关节关系图. 通常来讲,正确的模型生成的图应该是一个DAG, 并且`base_link`是唯一的根 (root node).
|
||||
|
||||
* 另一个注意事项:在Fusion 360中,单击'J'进行组件联结的时候,**部件1是child 而部件2是 parent**. 举个例子, 如果你要组装一个四轮小车,呐么在联结轮子和车体的时候车轮应该是联结里的部件1, 车体(此情况下是`base_link`)应该是联结里的部件2
|
||||
|
||||
* 以下是一个四轮车例子, 如果你希望你的的urdf如下所示`check_urdf simple_car.urdf`, 那你组装四个轮子的时候 BL, BR, FL, FR 都应该是部件1, base_link 是部件2.
|
||||
```
|
||||
robot name is: simple_car
|
||||
---------- Successfully Parsed XML ---------------
|
||||
root Link: base_link has 4 child(ren)
|
||||
child(1): BL_1
|
||||
child(2): BR_1
|
||||
child(3): FL_1
|
||||
child(4): FR_1
|
||||
```
|
||||
|
||||
2. 运行脚本并选择存储位置
|
||||
* P.S.运行脚本后,**不要保存**文件! DesignType会被设为“直接模式”,并会生成一些临时组件。这些更改你是肯定不会想要的。所以不要保存!如果不小心保存了记得回退。
|
||||
* 
|
||||
* 
|
||||
* 
|
||||
|
||||
3. 好啦,可以跑 `python hello_bullet.py` 试试啦!
|
||||
|
||||
## FAQ
|
||||
|
||||
### 出现Error时该怎么办?
|
||||
|
||||
* Bugs are usually caused by wrongly set up joints relationships
|
||||
* Nest-component support might also lead to undocumented bugs. So remove the nesting structure helps a lot.
|
||||
|
||||
我尝试了蛮多方法,但是导致错误的关节还是很难精准定位到,所以该脚本仍然无法优雅地显示警告和错误。因此如果你找不出模型出了什么问题,则可以试下这些操作:
|
||||
|
||||
1. 确保正确设置了每个关节 (parent and child 的关系,建议通过 Joint2Graphviz的DAG检查一下). 如果还是不行的话 --->
|
||||
2. 重新整理设计图,拆开嵌套组件重新组装. 如果还是不行的话 --->
|
||||
3. 尝试使用稳定版 [Branch: stable](https://github.com/yanshil/Fusion2Pyblluet/tree/stable).
|
||||
4. 试一下Fusion 360 的 debug mode,看看究竟出了什么问题 
|
||||
|
||||
### 怎样检查部件联结是不是搞对了哩?
|
||||
|
||||
参见 [Joint2Graphviz](https://github.com/yanshil/Joint2Graphviz)
|
||||
|
||||
### 如果我的默认单位不是mm呢?
|
||||
|
||||
那么你要改一下这部分代码了。`Bullet_URDF_Exporter/core/Link.py`. 搜 `scale`
|
||||
|
||||
(如果你发现其他地方也需要改,别忘了ping我一下,有可能有遗漏。。。)
|
||||
|
||||
```
|
||||
# visual
|
||||
visual = SubElement(link, 'visual')
|
||||
origin_v = SubElement(visual, 'origin')
|
||||
origin_v.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
geometry_v = SubElement(visual, 'geometry')
|
||||
mesh_v = SubElement(geometry_v, 'mesh')
|
||||
mesh_v.attrib = {'filename': self.repo + self.name + '.stl','scale':'0.001 0.001 0.001'} ## scale = 0.001 means mm to m. Modify it according if using another unit
|
||||
material = SubElement(visual, 'material')
|
||||
material.attrib = {'name':'silver'}
|
||||
|
||||
# collision
|
||||
collision = SubElement(link, 'collision')
|
||||
origin_c = SubElement(collision, 'origin')
|
||||
origin_c.attrib = {'xyz':' '.join([str(_) for _ in self.xyz]), 'rpy':'0 0 0'}
|
||||
geometry_c = SubElement(collision, 'geometry')
|
||||
mesh_c = SubElement(geometry_c, 'mesh')
|
||||
mesh_c.attrib = {'filename': self.repo + self.name + '.stl','scale':'0.001 0.001 0.001'} ## scale = 0.001 means mm to m. Modify it according if using another unit
|
||||
material = SubElement(visual, 'material')
|
||||
```
|
1
_config.yml
Normal file
|
@ -0,0 +1 @@
|
|||
theme: jekyll-theme-slate
|
BIN
imgs/1_plugin.png
Normal file
After Width: | Height: | Size: 334 KiB |
BIN
imgs/2_script.png
Normal file
After Width: | Height: | Size: 342 KiB |
BIN
imgs/3_success.png
Normal file
After Width: | Height: | Size: 360 KiB |
BIN
imgs/4_close.png
Normal file
After Width: | Height: | Size: 354 KiB |
BIN
imgs/5_files.png
Normal file
After Width: | Height: | Size: 2.4 KiB |
BIN
imgs/6_debug.PNG
Normal file
After Width: | Height: | Size: 230 KiB |
BIN
imgs/Error1.PNG
Normal file
After Width: | Height: | Size: 22 KiB |
BIN
imgs/Error2.PNG
Normal file
After Width: | Height: | Size: 213 KiB |
BIN
imgs/Error_graphviz1.png
Normal file
After Width: | Height: | Size: 73 KiB |
BIN
imgs/Error_graphviz2.png
Normal file
After Width: | Height: | Size: 117 KiB |