Skip to content

Nested components, as-built joints, MJCF joint ranges, and more #9

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
31 changes: 9 additions & 22 deletions Add-IN/ACDC4Robot/commands/ACDC4Robot/acdc4robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,14 @@ def get_link_joint_list(design: adsk.fusion.Design):
# try to solve the nested components problem
# but still not fully tested
for occ in occs:
if not utils.component_has_bodies(occ.component):
continue
# TODO: it seems use occ.joints.count will make it usable with occurrences? Test it
if occ.component.joints.count > 0:
# textPalette.writeText(str(occ.fullPathName))
continue
else:
# Only occurrence contains zero joint and has zero childOccurrences
# Only occurrence contains zero joint and has zero childOccurrences
# can be seen as a link
if occ.childOccurrences.count > 0:
# textPalette.writeText(str(occ.fullPathName))
Expand All @@ -53,6 +55,8 @@ def get_link_joint_list(design: adsk.fusion.Design):

for joint in root.allJoints:
joint_list.append(Joint(joint)) # add joint objects into joint_list
for joint in root.allAsBuiltJoints:
joint_list.append(Joint(joint)) # add joint objects into joint_list

return link_list, joint_list

Expand Down Expand Up @@ -134,9 +138,6 @@ def run():
constants.set_text_palette(textPalette)

try:
# Set design type into do not capture design history
design.designType = adsk.fusion.DesignTypes.DirectDesignType
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

From what I can tell, this shouldn't be necessary. I kept the design history enabled for my model and everything was okay.


# # Check the length unit of Fusion360
# if design.unitsManager.defaultLengthUnits != "m":
# ui.messageBox("Please set length unit to 'm'!", msg_box_title)
Expand Down Expand Up @@ -177,29 +178,15 @@ def run():
if simulator == "None":
ui.messageBox("Simulation environment is None.\n" +
"Please select a simulation environment.", msg_box_title)
elif simulator == "Gazebo":
# write to .urdf file
write.write_urdf(link_list, joint_list, save_folder, robot_name)
# export mesh files
export_stl(design, save_folder, link_list)
ui.messageBox("Finished exporting URDF for Gazebo.", msg_box_title)

elif simulator == "PyBullet":
elif simulator in ["Gazebo", "PyBullet", "MuJoCo"]:
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since the code in each condition was nearly identical, I combined them into a single block.

# write to .urdf file
write.write_urdf(link_list, joint_list, save_folder, robot_name)
# export mesh files
export_stl(design, save_folder, link_list)
# generate pybullet script
write.write_hello_pybullet(rdf, robot_name, save_folder)
ui.messageBox("Finished exporting URDF for PyBullet.", msg_box_title)

elif simulator == "MuJoCo":
# write to .urdf file
write.write_urdf(link_list, joint_list, save_folder, robot_name)
# export mesh files
export_stl(design, save_folder, link_list)

ui.messageBox("Finished exporting URDF for MuJoCo.", msg_box_title)
if simulator == 'PyBullet':
write.write_hello_pybullet(rdf, robot_name, save_folder)
ui.messageBox(f"Finished exporting URDF for {simulator}.", msg_box_title)

elif rdf == "SDFormat":
if simulator == "None":
Expand Down
62 changes: 51 additions & 11 deletions Add-IN/ACDC4Robot/core/joint.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,22 +4,28 @@

"""

from typing import Union
import adsk, adsk.fusion, adsk.core
from xml.etree.ElementTree import ElementTree, Element, SubElement
from ..commands.ACDC4Robot import constants
from . import utils
from . import math_operation as math_op
# from .link import Link

class Joint():
"""
Joint class for joint
"""

def __init__(self, joint: adsk.fusion.Joint) -> None:
def __init__(self, joint: Union[adsk.fusion.Joint, adsk.fusion.AsBuiltJoint]) -> None:
self.joint = joint
self.name = joint.name
self.parent = joint.occurrenceTwo # parent link of joint
self.child = joint.occurrenceOne
try:
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In some cases, like when creating a rigid joint to an origin (i.e. lock to world), fetching the occurrences throws an exception.

self.parent = joint.occurrenceTwo # parent link of joint
self.child = joint.occurrenceOne
except Exception as e:
textPalette: adsk.core.Palette = constants.get_text_palette()
textPalette.writeText(f"Invalid joint: {joint.name}: {str(e)}")
pass
# self.parent = Link(joint.occurrenceTwo) # parent link of joint
# self.child = Link(joint.occurrenceOne)

Expand All @@ -37,6 +43,19 @@ def get_name(self):
name = utils.get_valid_filename(self.name)
return name

def get_full_path_name(self):
"""
Return:
path: str
The joint name and parent component path
"""
# joint names inside each occurrence are identical
# but joint names in different occurrences can be the same, in which makes conflict
if self.child:
child_name = utils.get_valid_filename(self.child.fullPathName)
return f"{child_name}_{self.get_name()}"
return self.get_name()

def get_parent(self):
"""
Return name of parent link
Expand All @@ -59,6 +78,18 @@ def get_child(self):

return child_name

def has_origin(self) -> bool:
"""
Checks if the join has a parent origin geometry
Return: bool
"""
if hasattr(self.joint, 'geometry'):
return self.joint.geometry is not None
elif self.joint.geometryOrOriginTwo == adsk.fusion.JointOrigin:
return self.joint.geometryOrOriginTwo.geometry is not None
else:
return self.joint.geometryOrOriginTwo.origin is not None

def get_sdf_joint_type(self) -> str:
"""
Currently support following joint type:
Expand Down Expand Up @@ -144,7 +175,9 @@ def get_sdf_origin(self):
# I guess using child joint origin works just because they coincide together for all the text examples

# get parent joint origin as the child joint
if self.joint.geometryOrOriginTwo == adsk.fusion.JointOrigin:
if hasattr(self.joint, 'geometry'):
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Necessary for an as-built joint

w_P_Jc = self.joint.geometry.origin.asArray()
elif self.joint.geometryOrOriginTwo == adsk.fusion.JointOrigin:
w_P_Jc = self.joint.geometryOrOriginTwo.geometry.origin.asArray()
else:
w_P_Jc = self.joint.geometryOrOriginTwo.origin.asArray()
Expand Down Expand Up @@ -182,17 +215,24 @@ def get_joint_frame(self) -> adsk.core.Matrix3D:
translation unit: cm
"""
# get parent joint origin's coordinate w.r.t world frame
if self.joint.geometryOrOriginTwo == adsk.fusion.JointOrigin:
w_P_J = self.joint.geometryOrOriginTwo.geometry.origin.asArray()
if hasattr(self.joint, 'geometry'):
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As-built joint origin geometry.

geometry: adsk.fusion.JointGeometry = self.joint.geometry
if geometry is None:
return None
w_P_J = geometry.origin.asArray()
else:
w_P_J = self.joint.geometryOrOriginTwo.origin.asArray()
geometry: adsk.fusion.JointOrigin = self.joint.geometryOrOriginTwo
if self.joint.geometryOrOriginTwo == adsk.fusion.JointOrigin:
w_P_J = geometry.geometry.origin.asArray()
else:
w_P_J = geometry.origin.asArray()

w_P_J = [round(i, 6) for i in w_P_J]

# no matter jointGeometry or jointOrigin object, both have these properties
zAxis: adsk.core.Vector3D = self.joint.geometryOrOriginTwo.primaryAxisVector
xAxis: adsk.core.Vector3D = self.joint.geometryOrOriginTwo.secondaryAxisVector
yAxis: adsk.core.Vector3D = self.joint.geometryOrOriginTwo.thirdAxisVector
zAxis: adsk.core.Vector3D = geometry.primaryAxisVector
xAxis: adsk.core.Vector3D = geometry.secondaryAxisVector
yAxis: adsk.core.Vector3D = geometry.thirdAxisVector

origin = adsk.core.Point3D.create(w_P_J[0], w_P_J[1], w_P_J[2])

Expand Down
Loading