8000 Added new function to load STL models using NumPy-STL. Now accepts bo… · lordkeks/robotics-toolbox-python@d1b765c · GitHub
[go: up one dir, main page]

Skip to content

Commit d1b765c

Browse files
committed
Added new function to load STL models using NumPy-STL. Now accepts both ASCII and BINARY formats.
1 parent 3a30ba8 commit d1b765c

File tree

2 files changed

+69
-11
lines changed

2 files changed

+69
-11
lines changed

graphics/graphics_stl.py

Lines changed: 62 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
from vpython import *
22
from graphics.common_functions import *
3+
from stl import mesh
34

45

5-
# TODO maybe change input to include extension? Or have entire path as input?
66
def import_object_from_stl(filename):
77
"""
88
Import an stl object and convert it into a usable vpython object.
@@ -14,10 +14,11 @@ def import_object_from_stl(filename):
1414
:type filename: str
1515
:return: Compound object of a collection of triangles formed from an stl file.
1616
:rtype: class:`vpython.compound`
17-
"""
18-
# TODO: put error handling in case binary stl file used instead of ascii
1917
20-
# TODO: put error handling in case of bad file
18+
.. deprecated::
19+
A new function using numpy import is available. It accepts both ASCII and BINARY formats.
20+
"""
21+
raise DeprecationWarning("This function is outdated. Use import_object_from_numpy_stl")
2122

2223
# Open the file
2324
filepath = './graphics/models/' + filename + '.stl'
@@ -63,6 +64,63 @@ def import_object_from_stl(filename):
6364
return compound(triangles)
6465

6566

67+
def import_object_from_numpy_stl(filename):
68+
"""
69+
Import either an ASCII or BINARY file format of an STL file.
70+
The triangles will be combined into a single compound entity.
71+
72+
:param filename: Path of the stl file to import.
73+
:type filename: str
74+
:return: Compound object of a collection of triangles formed from an stl file.
75+
:rtype: class:`vpython.compound`
76+
"""
77+
# Load the mesh using NumPy-STL
78+
the_mesh = mesh.Mesh.from_file(filename)
79+
80+
num_faces = len(the_mesh.vectors)
81+
triangles = []
82+
83+
# For every face in the model
84+
for face in range(0, num_faces):
85+
# Get the (3) 3D points
86+
point0 = the_mesh.vectors[face][0]
87+
point1 = the_mesh.vectors[face][1]
88+
point2 = the_mesh.vectors[face][2]
89+
90+
# Get the normal direction for the face
91+
normal0 = the_mesh.normals[face][0]
92+
normal1 = the_mesh.normals[face][1]
93+
normal2 = the_mesh.normals[face][2]
94+
normal = vec(normal0, normal1, normal2)
95+
96+
# Create the VPython 3D points
97+
vertex0 = vertex(
98+
pos=vec 8000 (point0[0], point0[1], point0[2]),
99+
normal=normal,
100+
color=color.white
101+
)
102+
vertex1 = vertex(
103+
pos=vec(point1[0], point1[1], point1[2]),
104+
normal=normal,
105+
color=color.white
106+
)
107+
vertex2 = vertex(
108+
pos=vec(point2[0], point2[1], point2[2]),
109+
normal=normal,
110+
color=color.white
111+
)
112+
113+
# Combine them in a list
114+
vertices = [vertex0, vertex1, vertex2]
115+
116+
# Create a triangle using the points, and add it to the list
117+
triangles.append(triangle(vs=vertices))
118+
119+
# Return a compound of the triangles
120+
visual_mesh = compound(triangles)
121+
return visual_mesh
122+
123+
66124
def set_stl_origin(stl_obj, current_obj_origin, required_obj_origin):
67125
"""
68126
Move the object so the required origin is at (0, 0, 0). Then set the origin for the generated stl object.

graphics/model_puma560.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ def create_link_0():
3131
:rtype: class:`graphics.graphics_robot.RotationalJoint
3232
"""
3333
# Load the STL file into an object
34-
stl_obj = import_object_from_stl(filename='link0')
34+
stl_obj = import_object_from_numpy_stl('./graphics/models/link0.stl')
3535
# Orient the object so that it's origin and toolpoint in known locations
3636
# This way, rotations are relative to the correct 3D position of the object
3737
stl_obj_z_origin = stl_obj.pos.z - stl_obj.width / 2
@@ -60,7 +60,7 @@ def create_link_1():
6060
:rtype: class:`graphics.graphics_robot.StaticJoint
6161
"""
6262
# Load the STL file into an object
63-
stl_obj = import_object_from_stl(filename='link1')
63+
stl_obj = import_object_from_numpy_stl('./graphics/models/link1.stl')
6464
# Orient the object so that it's origin and toolpoint in known locations
6565
# This way, rotations are relative to the correct 3D position of the object
6666
stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))
@@ -92,7 +92,7 @@ def create_link_2():
9292
:rtype: class:`graphics.graphics_robot.RotationalJoint
9393
"""
9494
# Load the STL file into an object
95-
stl_obj = import_object_from_stl('link2')
95+
stl_obj = import_object_from_numpy_stl('./graphics/models/link2.stl')
9696
# Orient the object so that it's origin and toolpoint in known locations
9797
# This way, rotations are relative to the correct 3D position of the object
9898
stl_obj.rotate(angle=radians(-90), axis=x_axis_vector, origin=vector(0, 0, 0))
@@ -124,7 +124,7 @@ def create_link_3():
124124
:rtype: class:`graphics.graphics_robot.RotationalJoint
125125
"""
126126
# Load the STL file into an object
127-
stl_obj = import_object_from_stl('link3')
127+
stl_obj = import_object_from_numpy_stl('./graphics/models/link3.stl')
128128
# Orient the object so that it's origin and toolpoint in known locations
129129
# This way, rotations are relative to the correct 3D position of the object
130130
stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))
@@ -156,7 +156,7 @@ def create_link_4():
156156
:rtype: class:`graphics.graphics_robot.RotationalJoint
157157
"""
158158
# Load the STL file into an object
159-
stl_obj = import_object_from_stl('link4')
159+
stl_obj = import_object_from_numpy_stl('./graphics/models/link4.stl')
160160
# Orient the object so that it's origin and toolpoint in known locations
161161
# This way, rotations are relative to the correct 3D position of the object
162162
stl_obj.rotate(angle=radians(-90), axis=z_axis_vector, origin=vector(0, 0, 0))
@@ -187,7 +187,7 @@ def create_link_5():
187187
:rtype: class:`graphics.graphics_robot.RotationalJoint
188188
"""
189189
# Load the STL file into an object
190-
stl_obj = import_object_from_stl('link5')
190+
stl_obj = import_object_from_numpy_stl('./graphics/models/link5.stl')
191191
# Orient the object so that it's origin and toolpoint in known locations
192192
# This way, rotations are relative to the correct 3D position of the object
193193
stl_obj.rotate(angle=radians(90), axis=x_axis_vector, origin=vector(0, 0, 0))
@@ -218,7 +218,7 @@ def create_link_6():
218218
:rtype: class:`graphics.graphics_robot.Gripper
219219
"""
220220
# Load the STL file into an object
221-
stl_obj = import_object_from_stl('link6')
221+
stl_obj = import_object_from_numpy_stl('./graphics/models/link6.stl')
222222
# Orient the object so that it's origin and toolpoint in known locations
223223
# This way, rotations are relative to the correct 3D position of the object
224224
stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))

0 commit comments

Comments
 (0)
0