Skip to content

Commit e44a382

Browse files
Merge pull request #138 from compas-dev/documentation_updates
Documentation updates
2 parents dde7a08 + 8e12e9c commit e44a382

26 files changed

+4705
-8092
lines changed

CHANGELOG.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ Unreleased
1010
----------
1111

1212
**Added**
13+
* Documentation updates
1314

1415
**Changed**
1516

docs/examples.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,3 +11,7 @@ Here you can find some examples files for compas_slicer
1111

1212
examples/01_planar_slicing_simple
1313
examples/02_curved_slicing_simple
14+
examples/03_planar_slicing_vertical_sorting
15+
examples/04_gcode_generation
16+
examples/05_non_planar_slicing_on_custom_base
17+
examples/06_attributes_transfer

docs/examples/02_curved_slicing_simple.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,11 +9,11 @@ A general introduction of the concepts organization of compas_slicer can be foun
99

1010
Make sure to read the :ref:`example on simple planar slicing <compas_slicer_example_1>` before reading this example,
1111
as it explains the main concepts of compas_slicer.
12-
Having done that, in this example, we go through the basics of using the non-planar interpolation slicer.
12+
Having done that, in this example, we go through the basics of using the non-planar interpolation slicer, which generates
13+
paths by interpolating user-defined boundaries.
1314
This example uses the method described in `Print Paths KeyFraming <https://dl.acm.org/doi/fullHtml/10.1145/3424630.3425408>`_.
1415

15-
16-
.. figure:: figures/curved_slicing.PNG
16+
.. figure:: figures/02_curved_slicing.PNG
1717
:figclass: figure
1818
:class: figure-img img-fluid
1919

Lines changed: 93 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,93 @@
1+
.. _compas_slicer_example_3:
2+
3+
************************************
4+
Planar slicing with vertical sorting
5+
************************************
6+
7+
During the print of branching shell shapes, the layers can be sorted;
8+
- following a horizontal logic, with all paths that are on the same height being adjacent.
9+
- following a vertical logic, with all paths that are on the same branch being adjacent.
10+
The vertical sorting can enable significant reduction of the interruptions of the print and the traveling of the tool
11+
from one path to the next, as it is shown in the illustration below.
12+
13+
.. figure:: figures/03_print_organization_planar_slicing_vertical_sorting.png
14+
:figclass: figure
15+
:class: figure-img img-fluid
16+
17+
*Fabrication path using horizontal sorting (left), and vertical sorting (right). The traveling paths are shown with orange lines.*
18+
19+
In planar slicing, horizontal ordering of paths is the default method, while in non-planar slicing vertical ordering of paths is
20+
the default method. The example below demonstrates how planar paths can be sorted in a vertical logic.
21+
22+
.. code-block:: python
23+
24+
import os
25+
import logging
26+
27+
import compas_slicer.utilities as utils
28+
from compas_slicer.pre_processing import move_mesh_to_point
29+
from compas_slicer.slicers import PlanarSlicer
30+
from compas_slicer.post_processing import generate_brim
31+
from compas_slicer.post_processing import simplify_paths_rdp
32+
from compas_slicer.post_processing import sort_into_vertical_layers
33+
from compas_slicer.post_processing import reorder_vertical_layers
34+
from compas_slicer.post_processing import seams_smooth
35+
from compas_slicer.print_organization import PlanarPrintOrganizer
36+
from compas_slicer.print_organization import set_extruder_toggle
37+
from compas_slicer.print_organization import add_safety_printpoints
38+
from compas_slicer.print_organization import set_linear_velocity_constant
39+
from compas_slicer.print_organization import set_blend_radius
40+
from compas_slicer.utilities import save_to_json
41+
from compas.datastructures import Mesh
42+
from compas.geometry import Point
43+
44+
# ==============================================================================
45+
# Logging
46+
# ==============================================================================
47+
logger = logging.getLogger('logger')
48+
logging.basicConfig(format='%(levelname)s-%(message)s', level=logging.INFO)
49+
50+
# ==============================================================================
51+
# Select location of data folder and specify model to slice
52+
# ==============================================================================
53+
DATA = os.path.join(os.path.dirname(__file__), 'data')
54+
OUTPUT_DIR = utils.get_output_directory(DATA) # creates 'output' folder if it doesn't already exist
55+
MODEL = 'distorted_v_closed_mid_res.obj'
56+
57+
58+
def main():
59+
compas_mesh = Mesh.from_obj(os.path.join(DATA, MODEL))
60+
move_mesh_to_point(compas_mesh, Point(0, 0, 0))
61+
62+
# Slicing
63+
slicer = PlanarSlicer(compas_mesh, slicer_type="cgal", layer_height=5.0)
64+
slicer.slice_model()
65+
66+
# Sorting into vertical layers and reordering
67+
sort_into_vertical_layers(slicer, max_paths_per_layer=10)
68+
reorder_vertical_layers(slicer, align_with="x_axis")
69+
70+
# Post-processing
71+
generate_brim(slicer, layer_width=3.0, number_of_brim_offsets=5)
72+
simplify_paths_rdp(slicer, threshold=0.7)
73+
seams_smooth(slicer, smooth_distance=10)
74+
slicer.printout_info()
75+
save_to_json(slicer.to_data(), OUTPUT_DIR, 'slicer_data.json')
76+
77+
# PlanarPrintOrganization
78+
print_organizer = PlanarPrintOrganizer(slicer)
79+
print_organizer.create_printpoints()
80+
81+
set_extruder_toggle(print_organizer, slicer)
82+
add_safety_printpoints(print_organizer, z_hop=10.0)
83+
set_linear_velocity_constant(print_organizer, v=25.0)
84+
set_blend_radius(print_organizer, d_fillet=10.0)
85+
86+
print_organizer.printout_info()
87+
88+
printpoints_data = print_organizer.output_printpoints_dict()
89+
utils.save_to_json(printpoints_data, OUTPUT_DIR, 'out_printpoints.json')
90+
91+
92+
if __name__ == "__main__":
93+
main()
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
.. _compas_slicer_example_4:
2+
3+
************************************
4+
Gcode generation
5+
************************************
6+
7+
While compas slicer has been mostly developed for robotic printing, we can also export the gcode of the generated paths
8+
to materialize them in a typical desktop 3D printer. The gcode generation is still at a basic level and is a work in progress.
9+
10+
11+
.. code-block:: python
12+
13+
import os
14+
import logging
15+
import compas_slicer.utilities as utils
16+
from compas_slicer.pre_processing import move_mesh_to_point
17+
from compas_slicer.slicers import PlanarSlicer
18+
from compas_slicer.post_processing import generate_brim
19+
from compas_slicer.post_processing import simplify_paths_rdp
20+
from compas_slicer.post_processing import seams_smooth
21+
from compas_slicer.print_organization import PlanarPrintOrganizer
22+
from compas_slicer.print_organization import set_extruder_toggle
23+
from compas_slicer.utilities import save_to_json
24+
from compas_slicer.parameters import get_param
25+
26+
from compas.datastructures import Mesh
27+
from compas.geometry import Point
28+
29+
logger = logging.getLogger('logger')
30+
logging.basicConfig(format='%(levelname)s-%(message)s', level=logging.INFO)
31+
32+
DATA = os.path.join(os.path.dirname(__file__), 'data')
33+
OUTPUT_DIR = utils.get_output_directory(DATA) # creates 'output' folder if it doesn't already exist
34+
MODEL = 'simple_vase_open_low_res.obj'
35+
36+
37+
def main():
38+
39+
compas_mesh = Mesh.from_obj(os.path.join(DATA, MODEL))
40+
delta = get_param({}, key='delta', defaults_type='gcode') # boolean for delta printers
41+
print_volume_x = get_param({}, key='print_volume_x', defaults_type='gcode') # in mm
42+
print_volume_y = get_param({}, key='print_volume_y', defaults_type='gcode') # in mm
43+
if delta:
44+
move_mesh_to_point(compas_mesh, Point(0, 0, 0))
45+
else:
46+
move_mesh_to_point(compas_mesh, Point(print_volume_x/2, print_volume_y/2, 0))
47+
48+
# ----- slicing
49+
slicer = PlanarSlicer(compas_mesh, slicer_type="cgal", layer_height=4.5)
50+
slicer.slice_model()
51+
generate_brim(slicer, layer_width=3.0, number_of_brim_offsets=4)
52+
simplify_paths_rdp(slicer, threshold=0.6)
53+
seams_smooth(slicer, smooth_distance=10)
54+
slicer.printout_info()
55+
save_to_json(slicer.to_data(), OUTPUT_DIR, 'slicer_data.json')
56+
57+
# ----- print organization
58+
print_organizer = PlanarPrintOrganizer(slicer)
59+
print_organizer.create_printpoints()
60+
# Set fabrication-related parameters
61+
set_extruder_toggle(print_organizer, slicer)
62+
print_organizer.printout_info()
63+
64+
# create and output gcode
65+
gcode_parameters = {} # leave all to default
66+
gcode_text = print_organizer.output_gcode(gcode_parameters)
67+
utils.save_to_text_file(gcode_text, OUTPUT_DIR, 'my_gcode.gcode')
Lines changed: 70 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,70 @@
1+
.. _compas_slicer_example_5:
2+
3+
************************************
4+
Non-planar slicing on custom base
5+
************************************
6+
7+
In this example we describe the process of non-planar slicing of a mesh, generating paths that are an offset to its
8+
custom base. We are using the ScalarFieldSlicer, which generates paths as contours of a scalar field defined on every
9+
vertex of the mesh. In this case we create a scalar field with the distance of each vertex from the custom base.
10+
11+
.. figure:: figures/05_scalar_field_slicing.PNG
12+
:figclass: figure
13+
:class: figure-img img-fluid
14+
15+
*Result of scalar field slicing considering the distance of each vertex from the custom base.*
16+
17+
18+
.. code-block:: python
19+
20+
import logging
21+
from compas.geometry import distance_point_point
22+
from compas.datastructures import Mesh
23+
import os
24+
import compas_slicer.utilities as slicer_utils
25+
from compas_slicer.post_processing import simplify_paths_rdp
26+
from compas_slicer.slicers import ScalarFieldSlicer
27+
import compas_slicer.utilities as utils
28+
from compas_slicer.print_organization import ScalarFieldPrintOrganizer
29+
30+
logger = logging.getLogger('logger')
31+
logging.basicConfig(format='%(levelname)s-%(message)s', level=logging.INFO)
32+
33+
DATA_PATH = os.path.join(os.path.dirname(__file__), 'data')
34+
OUTPUT_PATH = slicer_utils.get_output_directory(DATA_PATH)
35+
MODEL = 'geom_to_slice.obj'
36+
BASE = 'custom_base.obj'
37+
38+
if __name__ == '__main__':
39+
40+
# --- load meshes
41+
mesh = Mesh.from_obj(os.path.join(DATA_PATH, MODEL))
42+
base = Mesh.from_obj(os.path.join(DATA_PATH, BASE))
43+
44+
# --- Create per-vertex scalar field (distance of every vertex from the custom base)
45+
pts = [mesh.vertex_coordinates(v_key, axes='xyz') for v_key in
46+
mesh.vertices()] # list of the vertex coordinates of the mesh as compas.geometry.Point instances
47+
_, projected_pts = utils.pull_pts_to_mesh_faces(base, pts) # list with projections of all mesh vertices on the mesh
48+
u = [distance_point_point(pt, proj_pt) for pt, proj_pt in
49+
zip(pts, projected_pts)] # list with distance between initial+projected pts (one per vertex)
50+
utils.save_to_json(u, OUTPUT_PATH, 'distance_field.json') # save distance field to json for visualization
51+
52+
# --- assign the scalar field to the mesh's attributes, under the name 'scalar_field'
53+
mesh.update_default_vertex_attributes({'scalar_field': 0.0})
54+
for i, (v_key, data) in enumerate(mesh.vertices(data=True)):
55+
data['scalar_field'] = u[i]
56+
57+
# --- Slice model by generating contours of scalar field
58+
slicer = ScalarFieldSlicer(mesh, u, no_of_isocurves=50)
59+
slicer.slice_model()
60+
# simplify_paths_rdp(slicer, threshold=0.3)
61+
slicer_utils.save_to_json(slicer.to_data(), OUTPUT_PATH, 'isocontours.json') # save results to json
62+
63+
# --- Print organization calculations (i.e. generation of printpoints with fabrication-related information)
64+
simplify_paths_rdp(slicer, threshold=0.3)
65+
print_organizer = ScalarFieldPrintOrganizer(slicer, parameters={}, DATA_PATH=DATA_PATH)
66+
print_organizer.create_printpoints()
67+
68+
print_organizer.printout_info()
69+
printpoints_data = print_organizer.output_printpoints_dict()
70+
utils.save_to_json(printpoints_data, OUTPUT_PATH, 'out_printpoints.json') # save results to json
Lines changed: 106 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,106 @@
1+
.. _compas_slicer_example_6:
2+
3+
************************************
4+
Transferring attributes to PrintPoints
5+
************************************
6+
7+
Often in 3D printing we need to transfer information from the mesh that is being sliced to the PrintPoints that
8+
are used in the fabrication process. We might want, for example, to print paths that are generated from different parts of
9+
the geometry using different parameters. This is enabled by the *transfer_mesh_attributes_to_printpoints()* function, as
10+
shown in the example below. During the slicing process each printpoint is projected to the closest mesh face.
11+
It takes directly all the face attributes, and it takes the averaged vertex attributes of the face vertices using
12+
barycentric coordinates.
13+
14+
.. figure:: figures/06_attributes.png
15+
:figclass: figure
16+
:class: figure-img img-fluid
17+
18+
*PrintPoints with visualization of the attribute: overhang angle of the underlying mesh.*
19+
20+
21+
.. code-block:: python
22+
23+
import logging
24+
import os
25+
from compas.geometry import Point, Vector, distance_point_plane, normalize_vector
26+
from compas.datastructures import Mesh
27+
import compas_slicer.utilities as slicer_utils
28+
from compas_slicer.post_processing import simplify_paths_rdp
29+
from compas_slicer.slicers import PlanarSlicer
30+
import compas_slicer.utilities.utils as utils
31+
from compas_slicer.utilities.attributes_transfer import transfer_mesh_attributes_to_printpoints
32+
from compas_slicer.print_organization import PlanarPrintOrganizer
33+
import numpy as np
34+
35+
logger = logging.getLogger('logger')
36+
logging.basicConfig(format='%(levelname)s-%(message)s', level=logging.INFO)
37+
38+
DATA_PATH = os.path.join(os.path.dirname(__file__), 'data')
39+
OUTPUT_PATH = slicer_utils.get_output_directory(DATA_PATH)
40+
MODEL = 'distorted_v_closed_low_res.obj'
41+
42+
if __name__ == '__main__':
43+
# load mesh
44+
mesh = Mesh.from_obj(os.path.join(DATA_PATH, MODEL))
45+
46+
# --------------- Add attributes to mesh
47+
# Face attributes can be anything (ex. float, bool, array, text ...)
48+
# Vertex attributes can only be entities that can be meaningfully multiplied with a float (ex. float, np.array ...)
49+
50+
# overhand attribute - Scalar value (per face)
51+
mesh.update_default_face_attributes({'overhang': 0.0})
52+
for f_key, data in mesh.faces(data=True):
53+
face_normal = mesh.face_normal(f_key, unitized=True)
54+
data['overhang'] = Vector(0.0, 0.0, 1.0).dot(face_normal)
55+
56+
# face looking towards the positive y axis - Boolean value (per face)
57+
mesh.update_default_face_attributes({'positive_y_axis': False})
58+
for f_key, data in mesh.faces(data=True):
59+
face_normal = mesh.face_normal(f_key, unitized=True)
60+
is_positive_y = Vector(0.0, 1.0, 0.0).dot(face_normal) > 0 # boolean value
61+
data['positive_y_axis'] = is_positive_y
62+
63+
# distance from plane - Scalar value (per vertex)
64+
mesh.update_default_vertex_attributes({'dist_from_plane': 0.0})
65+
plane = (Point(0.0, 0.0, -30.0), Vector(0.0, 0.5, 0.5))
66+
for v_key, data in mesh.vertices(data=True):
67+
v_coord = mesh.vertex_coordinates(v_key, axes='xyz')
68+
data['dist_from_plane'] = distance_point_plane(v_coord, plane)
69+
70+
# direction towards point - Vector value (per vertex)
71+
mesh.update_default_vertex_attributes({'direction_to_pt': 0.0})
72+
pt = Point(4.0, 1.0, 0.0)
73+
for v_key, data in mesh.vertices(data=True):
74+
v_coord = mesh.vertex_coordinates(v_key, axes='xyz')
75+
data['direction_to_pt'] = np.array(normalize_vector(Vector.from_start_end(v_coord, pt)))
76+
77+
# --------------- Slice mesh
78+
slicer = PlanarSlicer(mesh, slicer_type="default", layer_height=5.0)
79+
slicer.slice_model()
80+
simplify_paths_rdp(slicer, threshold=1.0)
81+
slicer_utils.save_to_json(slicer.to_data(), OUTPUT_PATH, 'slicer_data.json')
82+
83+
# --------------- Create printpoints
84+
print_organizer = PlanarPrintOrganizer(slicer)
85+
print_organizer.create_printpoints()
86+
87+
# --------------- Transfer mesh attributes to printpoints
88+
transfer_mesh_attributes_to_printpoints(mesh, print_organizer.printpoints_dict)
89+
90+
# --------------- Save printpoints to json (only json-serializable attributes are saved)
91+
printpoints_data = print_organizer.output_printpoints_dict()
92+
utils.save_to_json(printpoints_data, OUTPUT_PATH, 'out_printpoints.json')
93+
94+
# --------------- Print the info to see the attributes of the printpoints (you can also visualize them on gh)
95+
print_organizer.printout_info()
96+
97+
# --------------- Save printpoints attributes for visualization
98+
overhangs_list = print_organizer.get_printpoints_attribute(attr_name='overhang')
99+
positive_y_axis_list = print_organizer.get_printpoints_attribute(attr_name='positive_y_axis')
100+
dist_from_plane_list = print_organizer.get_printpoints_attribute(attr_name='dist_from_plane')
101+
direction_to_pt_list = print_organizer.get_printpoints_attribute(attr_name='direction_to_pt')
102+
103+
utils.save_to_json(overhangs_list, OUTPUT_PATH, 'overhangs_list.json')
104+
utils.save_to_json(positive_y_axis_list, OUTPUT_PATH, 'positive_y_axis_list.json')
105+
utils.save_to_json(dist_from_plane_list, OUTPUT_PATH, 'dist_from_plane_list.json')
106+
utils.save_to_json(utils.point_list_to_dict(direction_to_pt_list), OUTPUT_PATH, 'direction_to_pt_list.json')
376 KB
Loading
656 KB
Loading
312 KB
Loading

0 commit comments

Comments
 (0)