8000 Importing STL objects by micah-huth · Pull Request #43 · petercorke/robotics-toolbox-python · GitHub
[go: up one dir, main page]

Skip to content

Importing STL objects #43

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

Merged
merged 3 commits into from
Jun 24, 2020
Merged
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
39 changes: 26 additions & 13 deletions graphics/graphics_grid.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,23 @@ def __init__(self):
# Save the current camera settings
self.camera_pos = scene.camera.pos
self.camera_axes = scene.camera.axis

# Private parameters for indexing in grid_object
self.__xy_plane_idx = 0
self.__xz_plane_idx = 1
self.__yz_plane_idx = 2
self.__planes_idx = 0
self.__labels_idx = 1

# Initialise a grid object
# grid_object[0] will always be the 3 plane graphics. [XY, XZ, YZ] (alphabetical in order and connection)
# grid_object[1] will always be the labels. There is always a certain number of indices.
# Order is [x-plane numbers, "X", y-plane numbers, "Y", z-plane numbers, "Z"]
self.grid_object = [[], []]
self.__init_grid()



def __init_grid(self):
"""
Initialise the grid along the x, y, z axes.
Expand All @@ -25,10 +35,10 @@ def __init_grid(self):
relative_cam = True # Whether the grid follows the camera rotation and movement

the_grid = self.__create_grid_objects(relative_cam, num_squares)
self.grid_object[0] = the_grid
self.grid_object[self.__planes_idx] = the_grid

# Update the labels instead of recreating them
update_grid_numbers(self.grid_object[1], relative_cam, num_squares)
update_grid_numbers(self.grid_object[self.__labels_idx], relative_cam, num_squares)

def __create_grid_objects(self, bool_camera_relative, num_squares):
"""
Expand Down Expand Up @@ -124,7 +134,10 @@ def __create_grid_objects(self, bool_camera_relative, num_squares):
yz_plane = compound(yz_lines)

# Combine all into one list
grid = [xy_plane, xz_plane, yz_plane]
grid = [None, None, None]
grid[self.__xy_plane_idx] = xy_plane
grid[self.__xz_plane_idx] = xz_plane
grid[self.__yz_plane_idx] = yz_plane

return grid

Expand Down Expand Up @@ -174,21 +187,21 @@ def __move_grid_objects(self, bool_camera_relative, num_squares):

# XY Plane
if camera_axes.z < 0:
self.grid_object[0][0].pos = vector(x_middle, y_middle, min_z_coord)
self.grid_object[self.__planes_idx][self.__xy_plane_idx].pos = vector(x_middle, y_middle, min_z_coord)
else:
self.grid_object[0][0].pos = vector(x_middle, y_middle, max_z_coord)
self.grid_object[self.__planes_idx][self.__xy_plane_idx].pos = vector(x_middle, y_middle, max_z_coord)

# XZ Plane
if camera_axes.y < 0:
self.grid_object[0][1].pos = vector(x_middle, min_y_coord, z_middle)
self.grid_object[self.__planes_idx][self.__xz_plane_idx].pos = vector(x_middle, min_y_coord, z_middle)
else:
self.grid_object[0][1].pos = vector(x_middle, max_y_coord, z_middle)
self.grid_object[self.__planes_idx][self.__xz_plane_idx].pos = vector(x_middle, max_y_coord, z_middle)

# YZ Plane
if camera_axes.x < 0:
self.grid_object[0][2].pos = vector(min_x_coord, y_middle, z_middle)
self.grid_object[self.__planes_idx][self.__yz_plane_idx].pos = vector(min_x_coord, y_middle, z_middle)
else:
self.grid_object[0][2].pos = vector(max_x_coord, y_middle, z_middle)
self.grid_object[self.__planes_idx][self.__yz_plane_idx].pos = vector(max_x_coord, y_middle, z_middle)

def update_grid(self):
"""
Expand All @@ -212,7 +225,7 @@ def update_grid(self):
num_squares = 10 # Length of the grid in each direction (in units)
relative_cam = True # Whether the grid follows the camera rotation and movement
self.__move_grid_objects(relative_cam, num_squares)
update_grid_numbers(self.grid_object[1], relative_cam, num_squares)
update_grid_numbers(self.grid_object[self.__labels_idx], relative_cam, num_squares)

# Else save current grid
else:
Expand All @@ -226,9 +239,9 @@ def set_visibility(self, is_visible):
:param is_visible: Boolean of whether to display the grid
:type is_visible: bool
"""
for plane in self.grid_object[0]:
for plane in self.grid_object[self.__planes_idx]:
plane.visible = is_visible
for number in self.grid_object[1]:
for number in self.grid_object[self.__labels_idx]:
number.visible = is_visible

def clear_scene(self):
Expand All @@ -246,7 +259,7 @@ def clear_scene(self):
and have the user assume they are all deleted. However, all objects can be redisplayed by setting the visibility
"""
# Save current grid visibility
grid_visibility = self.grid_object[0][0].visible
grid_visibility = self.grid_object[self.__planes_idx][self.__xy_plane_idx].visible

# Set all objects invisible
for scene_object in scene.objects:
Expand Down
66 changes: 62 additions & 4 deletions graphics/graphics_stl.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
from vpython import *
from graphics.common_functions import *
from stl import mesh


# TODO maybe change input to include extension? Or have entire path as input?
def import_object_from_stl(filename):
"""
Import an stl object and convert it into a usable vpython object.
Expand All @@ -14,10 +14,11 @@ def import_object_from_stl(filename):
:type filename: str
:return: Compound object of a collection of triangles formed from an stl file.
:rtype: class:`vpython.compound`
"""
# TODO: put error handling in case binary stl file used instead of ascii

# TODO: put error handling in case of bad file
.. deprecated::
A new function using numpy import is available. It accepts both ASCII and BINARY formats.
"""
raise DeprecationWarning("This function is outdated. Use import_object_from_numpy_stl")

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


def import_object_from_numpy_stl(filename):
"""
Import either an ASCII or BINARY file format of an STL file.
The triangles will be combined into a single compound entity.

:param filename: Path of the stl file to import.
:type filename: str
:return: Compound object of a collection of triangles formed from an stl file.
:rtype: class:`vpython.compound`
"""
# Load the mesh using NumPy-STL
the_mesh = mesh.Mesh.from_file(filename)

num_faces = len(the_mesh.vectors)
triangles = []

# For every face in the model
for face in range(0, num_faces):
# Get the (3) 3D points
point0 = the_mesh.vectors[face][0]
point1 = the_mesh.vectors[face][1]
point2 = the_mesh.vectors[face][2]

# Get the normal direction for the face
normal0 = the_mesh.normals[face][0]
normal1 = the_mesh.normals[face][1]
normal2 = the_mesh.normals[face][2]
normal = vec(normal0, normal1, normal2)

# Create the VPython 3D points
vertex0 = vertex(
pos=vec(point0[0], point0[1], point0[2]),
normal=normal,
color=color.white
)
vertex1 = vertex(
pos=vec(point1[0], point1[1], point1[2]),
normal=normal,
color=color.white
)
vertex2 = vertex(
pos=vec(point2[0], point2[1], point2[2]),
normal=normal,
color=color.white
)

# Combine them in a list
vertices = [vertex0, vertex1, vertex2]

# Create a triangle using the points, and add it to the list
triangles.append(triangle(vs=vertices))

# Return a compound of the triangles
visual_mesh = compound(triangles)
return visual_mesh


def set_stl_origin(stl_obj, current_obj_origin, required_obj_origin):
"""
Move the object so the required origin is at (0, 0, 0). Then set the origin for the generated stl object.
Expand Down
14 changes: 7 additions & 7 deletions graphics/model_puma560.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ def create_link_0():
:rtype: class:`graphics.graphics_robot.RotationalJoint
"""
# Load the STL file into an object
stl_obj = import_object_from_stl(filename='link0')
stl_obj = import_object_from_numpy_stl('./graphics/models/link0.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj_z_origin = stl_obj.pos.z - stl_obj.width / 2
Expand Down Expand Up @@ -60,7 +60,7 @@ def create_link_1():
:rtype: class:`graphics.graphics_robot.StaticJoint
"""
# Load the STL file into an object
stl_obj = import_object_from_stl(filename='link1')
stl_obj = import_object_from_numpy_stl('./graphics/models/link1.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))
Expand Down Expand Up @@ -92,7 +92,7 @@ def create_link_2():
:rtype: class:`graphics.graphics_robot.RotationalJoint
"""
# Load the STL file into an object
stl_obj = import_object_from_stl('link2')
stl_obj = import_object_from_numpy_stl('./graphics/models/link2.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj.rotate(angle=radians(-90), axis=x_axis_vector, origin=vector(0, 0, 0))
Expand Down Expand Up @@ -124,7 +124,7 @@ def create_link_3():
:rtype: class:`graphics.graphics_robot.RotationalJoint
"""
# Load the STL file into an object
stl_obj = import_object_from_stl('link3')
stl_obj = import_object_from_numpy_stl('./graphics/models/link3.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))
Expand Down Expand Up @@ -156,7 +156,7 @@ def create_link_4():
:rtype: class:`graphics.graphics_robot.RotationalJoint
"""
# Load the STL file into an object
stl_obj = import_object_from_stl('link4')
stl_obj = import_object_from_numpy_stl('./graphics/models/link4.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj.rotate(angle=radians(-90), axis=z_axis_vector, origin=vector(0, 0, 0))
Expand Down Expand Up @@ -187,7 +187,7 @@ def create_link_5():
:rtype: class:`graphics.graphics_robot.RotationalJoint
"""
# Load the STL file into an object
stl_obj = import_object_from_stl('link5')
stl_obj = import_object_from_numpy_stl('./graphics/models/link5.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj.rotate(angle=radians(90), axis=x_axis_vector, origin=vector(0, 0, 0))
Expand Down Expand Up @@ -218,7 +218,7 @@ def create_link_6():
:rtype: class:`graphics.graphics_robot.Gripper
"""
# Load the STL file into an object
stl_obj = import_object_from_stl('link6')
stl_obj = import_object_from_numpy_stl('./graphics/models/link6.stl')
# Orient the object so that it's origin and toolpoint in known locations
# This way, rotations are relative to the correct 3D position of the object
stl_obj.rotate(angle=radians(90), axis=y_axis_vector, origin=vector(0, 0, 0))
Expand Down
0