Skip to content

Commit

Permalink
Added fix for ball mates
Browse files Browse the repository at this point in the history
  • Loading branch information
senthurayyappan committed Dec 14, 2024
1 parent d09b539 commit c323304
Show file tree
Hide file tree
Showing 7 changed files with 37 additions and 162 deletions.
7 changes: 2 additions & 5 deletions docs/tutorials/edit.md
Original file line number Diff line number Diff line change
Expand Up @@ -115,14 +115,11 @@ This will save an image of the assembly graph (`bike.png`) in your current worki
Convert the assembly into a URDF file for robotics applications:

```python
from onshape_api.urdf import get_urdf_components
from onshape_api.urdf import get_robot
from onshape_api.models.robot import Robot

# Generate URDF links and joints
links, joints = get_urdf_components(assembly, graph, root_node, parts, mates, relations, client)

# Create and save the URDF file
robot = Robot(name="bike", links=links, joints=joints)
robot = get_robot(assembly, graph, root_node, parts, mates, relations, client, "bike")
robot.save("bike.urdf")
```

Expand Down
4 changes: 2 additions & 2 deletions docs/tutorials/export.md
Original file line number Diff line number Diff line change
Expand Up @@ -100,17 +100,17 @@ This will save a PNG file of the assembly graph in your current working director
Convert the parsed assembly data into a URDF file:

```python
links, joints = osa.get_urdf_components(
robot = osa.get_robot(
assembly=assembly,
graph=graph,
root_node=root_node,
parts=parts,
mates=mates,
relations=relations,
client=client,
robot_name=f"{assembly.document.name + '-' + assembly.name}",
)

robot = osa.Robot(name=f"{assembly.document.name + '-' + assembly.name}", links=links, joints=joints)
robot.save(f"{assembly.document.name + '-' + assembly.name}.urdf")
```

Expand Down
3 changes: 1 addition & 2 deletions examples/edit/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,7 @@
mates, relations = get_mates_and_relations(assembly, subassemblies, rigid_subassemblies, id_to_name_map, parts)

graph, root_node = create_graph(occurrences=occurrences, instances=instances, parts=parts, mates=mates)
plot_graph(graph, "bike.png")

robot = get_robot(assembly, graph, root_node, parts, mates, relations, client, "test")
robot.show()
plot_graph(graph, "bike.png")
robot.save()
8 changes: 3 additions & 5 deletions examples/export/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,7 @@
from onshape_api.log import LOGGER, LogLevel
from onshape_api.models.document import Document
from onshape_api.parse import get_instances, get_mates_and_relations, get_parts, get_subassemblies
from onshape_api.robot import Robot
from onshape_api.urdf import get_urdf_components
from onshape_api.urdf import get_robot
from onshape_api.utilities.helpers import save_model_as_json

SCRIPT_DIRECTORY = os.path.dirname(os.path.realpath(__file__))
Expand Down Expand Up @@ -45,15 +44,14 @@
)
plot_graph(graph, f"{assembly_robot_name}.png")

links, joints, assets = get_urdf_components(
robot = get_robot(
assembly=assembly,
graph=graph,
root_node=root_node,
parts=parts,
mates=mates,
relations=relations,
client=client,
robot_name=assembly_robot_name,
)

robot = Robot(name=assembly_robot_name, links=links, joints=joints, assets=assets)
robot.save()
14 changes: 14 additions & 0 deletions onshape_api/models/link.py
Original file line number Diff line number Diff line change
Expand Up @@ -352,6 +352,20 @@ def from_xml(cls, xml: etree.Element) -> "Inertia":
iyz = float(xml.get("iyz"))
return cls(ixx, iyy, izz, ixy, ixz, iyz)

@classmethod
def zero_inertia(cls) -> "Inertia":
"""
Create an inertia tensor with zero values.
Returns:
The inertia tensor with zero values.
Examples:
>>> Inertia.zero_inertia()
Inertia(ixx=0.0, iyy=0.0, izz=0.0, ixy=0.0, ixz=0.0, iyz=0.0)
"""
return cls(0.0, 0.0, 0.0, 0.0, 0.0, 0.0)


@dataclass
class Material:
Expand Down
1 change: 1 addition & 0 deletions onshape_api/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,7 @@ def to_urdf(self) -> str:
link_data.to_xml(robot) # Assuming Link has `to_xml`
else:
LOGGER.warning(f"Link {link_name} has no data.")
print(link_data)

# Add joints
for parent, child, joint_data in self.graph.edges(data="data"):
Expand Down
162 changes: 14 additions & 148 deletions onshape_api/urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
)
from onshape_api.parse import CHILD, MATE_JOINER, PARENT, RELATION_PARENT
from onshape_api.robot import Robot
from onshape_api.utilities.helpers import get_sanitized_name, make_unique_keys, make_unique_name
from onshape_api.utilities.helpers import get_sanitized_name

SCRIPT_DIR = os.path.dirname(__file__)

Expand Down Expand Up @@ -256,9 +256,19 @@ def get_robot_joint(
elif mate.mateType == MateType.BALL:
dummy_x = Link(
name=f"{parent}-{get_sanitized_name(mate.name)}-x",
inertial=InertialLink(
mass=0.0,
inertia=Inertia.zero_inertia(),
origin=Origin.zero_origin(),
),
)
dummy_y = Link(
name=f"{parent}-{get_sanitized_name(mate.name)}-y",
inertial=InertialLink(
mass=0.0,
inertia=Inertia.zero_inertia(),
origin=Origin.zero_origin(),
),
)

links = [dummy_x, dummy_y]
Expand Down Expand Up @@ -370,149 +380,6 @@ def get_topological_mates(
return topological_mates, topological_relations


def get_urdf_components(
assembly: Assembly,
graph: DiGraph,
root_node: str,
parts: dict[str, Part],
mates: dict[str, MateFeatureData],
relations: dict[str, MateRelationFeatureData],
client: Client,
) -> tuple[dict[str, Link], dict[str, BaseJoint], dict[str, Asset]]:
"""
Generate URDF links and joints from an Onshape assembly.
Args:
assembly: The Onshape assembly object.
graph: The graph representation of the assembly.
parts: The dictionary of parts in the assembly.
mates: The dictionary of mates in the assembly.
client: The Onshape client object to use for sending API requests.
Returns:
tuple[list[Link], list[BaseJoint]]: The generated URDF links and joints.
Examples:
>>> get_urdf_components(assembly, graph, parts, mates, client)
(
[
Link(name='root', visual=VisualLink(...), collision=CollisionLink(...), inertial=InertialLink(...)),
Link(name='link1', visual=VisualLink(...), collision=CollisionLink(...), inertial=InertialLink(...)),
Link(name='link2', visual=VisualLink(...), collision=CollisionLink(...), inertial=InertialLink(...))
],
[
RevoluteJoint(...),
FixedJoint(...),
]
)
"""
joints = []
links = []

links_map = {}
joints_map = {}
assets_map = {}

parts_traversed_map: dict[str, str] = {}

topological_mates, topological_relations = get_topological_mates(graph, mates, relations)

stl_to_link_tf_map = {}

LOGGER.info(f"Processing root node: {root_node}")

root_link, stl_to_root_tf, _asset = get_robot_link(
name=root_node, part=parts[root_node], wid=assembly.document.wid, client=client, mate=None
)

links.append(root_link)
parts_traversed_map[root_node] = parts[root_node].uid
assets_map[root_node] = _asset
stl_to_link_tf_map[root_node] = stl_to_root_tf

LOGGER.info(f"Processing remaining {len(graph.nodes) - 1} nodes using {len(graph.edges)} edges")

# reorder the edges to start with the root node
for edge in graph.edges:
parent, child = edge
mate_key = f"{parent}{MATE_JOINER}{child}"
LOGGER.info(f"Processing edge: {parent} -> {child}")
parent_tf = stl_to_link_tf_map[parent]

if parent not in parts or child not in parts:
LOGGER.warning(f"Part {parent} or {child} not found in parts")
# remove the edge from the graph?
continue

relation = topological_relations.get(topological_mates[mate_key].id)

if relation:
multiplier = 1.0
if relation.relationType == RelationType.RACK_AND_PINION:
multiplier = relation.relationLength

elif relation.relationType == RelationType.GEAR or relation.relationType == RelationType.LINEAR:
multiplier = relation.relationRatio

joint_mimic = JointMimic(
joint=get_joint_name(relation.mates[RELATION_PARENT].featureId, topological_mates),
multiplier=multiplier,
offset=0.0,
)
else:
joint_mimic = None

joint_list, link_list = get_robot_joint(
parent,
child,
topological_mates[mate_key],
parent_tf,
joint_mimic,
is_rigid_assembly=parts[parent].isRigidAssembly,
)
links.extend(link_list)
joints.extend(joint_list)

link, stl_to_link_tf, asset = get_robot_link(
child,
parts[child],
assembly.document.wid,
client,
topological_mates[mate_key],
)

stl_to_link_tf_map[child] = stl_to_link_tf
assets_map[child] = asset

if child not in parts_traversed_map:
links.append(link)
parts_traversed_map[child] = parts[child].uid
elif child in parts_traversed_map and parts_traversed_map[child] != parts[child].uid:
LOGGER.warning(f"Part shares the same name but different UID: {child}")
LOGGER.info("Still adding the link with modified unique name.")
unique_name = make_unique_name(link.name, set(parts_traversed_map))
parts_traversed_map[unique_name] = parts[child].uid
link.name = unique_name
links.append(link)
else:
LOGGER.warning(f"Part {child} already traversed. Skipping.")
continue

unique_joint_key_map = make_unique_keys([joint.name for joint in joints])
unique_link_key_map = make_unique_keys([link.name for link in links])

for joint_key in unique_joint_key_map:
joints[unique_joint_key_map[joint_key]].name = joint_key
joints_map[joint_key] = joints[unique_joint_key_map[joint_key]]

for link_key in unique_link_key_map:
links[unique_link_key_map[link_key]].name = link_key
links_map[link_key] = links[unique_link_key_map[link_key]]

return links_map, joints_map, assets_map


def get_robot(
assembly: Assembly,
graph: DiGraph,
Expand Down Expand Up @@ -595,19 +462,18 @@ def get_robot(
assets_map[child] = asset

if child not in robot.graph:
print(f"Link: {link}")
robot.add_link(link)
else:
LOGGER.warning(f"Link {child} already exists in the robot graph. Skipping.")

for joint in joint_list:
robot.add_joint(joint)

for link in link_list:
if link.name not in robot.graph:
robot.add_link(link)
else:
LOGGER.warning(f"Link {link.name} already exists in the robot graph. Skipping.")

for joint in joint_list:
robot.add_joint(joint)

robot.assets = assets_map
return robot

0 comments on commit c323304

Please sign in to comment.