Archive Note: I will no longer sutdy and work in Robitics. Please fork and develop on your needs.
简体中文 | English
Developed from @syuntoku14/fusion2urdf.
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:
03/03/2021: Pull the fix for xyz calculation from 01/09/2021 commit d2e754086f092ac81c481a0c3862e3cecb1f4dfe
in syuntoku14/fusion2urdf
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
03/25/2020: Supporting exportation of nested components.
Add this script into Fusion 360 via Tools -> Add-Ins
。
and ()
)base_link
Unit should be mm (See FAQ if it's not)
A base_link
Your file should not conatin extra file link. If any, right click on the component, do 'Break Link'
Check component and joint names (Set English as the language if necessary)
IMPORTANT! Set up joints properly
Supplementary script: Joint2Graphviz will generate a txt file capable for Graphviz. Copy the content to WebGraphviz 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
Run the script and select storing location
Enjoy from python hello_bullet.py
!
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:
A supporting script here: Joint2Graphviz for details
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')