Skip to content

Commit b175d57

Browse files
ADD skeletonization and slicer.
1 parent 35ffbbe commit b175d57

File tree

14 files changed

+8819
-1888
lines changed

14 files changed

+8819
-1888
lines changed

CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -230,3 +230,6 @@ add_nanobind_module(meshing_ext src/meshing.cpp)
230230
add_nanobind_module(intersections_ext src/intersections.cpp)
231231
add_nanobind_module(measure_ext src/measure.cpp)
232232
add_nanobind_module(reconstruction_ext src/reconstruction.cpp)
233+
add_nanobind_module(skeletonization_ext src/skeletonization.cpp)
234+
add_nanobind_module(slicer_ext src/slicer.cpp)
235+

data/elephant.off

Lines changed: 8336 additions & 1888 deletions
Large diffs are not rendered by default.
Lines changed: 56 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
import math
2+
from pathlib import Path
3+
4+
from compas.datastructures import Mesh
5+
from compas.geometry import Polyline
6+
from compas.geometry import Rotation
7+
from compas.geometry import Scale
8+
from compas.geometry import Translation
9+
from compas_viewer import Viewer
10+
from line_profiler import profile
11+
12+
from compas_cgal.skeletonization import mesh_skeleton
13+
14+
15+
@profile
16+
def main():
17+
"""Skeletonize a mesh."""
18+
19+
input_file = Path(__file__).parent.parent.parent / "data" / "elephant.off"
20+
21+
rotation_x = Rotation.from_axis_and_angle([1, 0, 0], math.radians(60))
22+
rotation_y = Rotation.from_axis_and_angle([0, 1, 0], math.radians(5))
23+
rotation = rotation_y * rotation_x
24+
scale = Scale.from_factors([5, 5, 5])
25+
translation = Translation.from_vector([0, 0, 2])
26+
27+
mesh = Mesh.from_off(input_file).transformed(translation * rotation * scale)
28+
# mesh = mesh.subdivided("loop")
29+
v, f = mesh.to_vertices_and_faces(triangulated=True)
30+
31+
skeleton_edges = mesh_skeleton((v, f))
32+
33+
polylines = []
34+
for start_point, end_point in skeleton_edges:
35+
polyline = Polyline([start_point, end_point])
36+
polylines.append(polyline)
37+
38+
return mesh, polylines
39+
40+
41+
mesh, polylines = main()
42+
43+
# ==============================================================================
44+
# Visualize
45+
# ==============================================================================
46+
47+
viewer = Viewer()
48+
viewer.renderer.camera.target = [0, 0, 1.5]
49+
viewer.renderer.camera.position = [-5, -5, 1.5]
50+
51+
viewer.scene.add(mesh, opacity=0.5, show_points=False)
52+
53+
for polyline in polylines:
54+
viewer.scene.add(polyline, linewidth=5, show_points=True)
55+
56+
viewer.show()
Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
Mesh Skeletonization
2+
====================
3+
4+
This example demonstrates how to compute the geometric skeleton of a triangle mesh using COMPAS CGAL.
5+
6+
Key Features:
7+
8+
* Loading and transforming OFF mesh files
9+
* Mesh subdivision using Loop scheme
10+
* Skeleton computation using mean curvature flow
11+
* Visualization of mesh and skeleton polylines
12+
13+
.. figure:: /_images/example_skeletonization.png
14+
:figclass: figure
15+
:class: figure-img img-fluid
16+
17+
.. literalinclude:: example_skeletonization.py
18+
:language: python

docs/examples/example_slicer.py

Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
import math
2+
from pathlib import Path
3+
4+
import numpy as np
5+
from compas.datastructures import Mesh
6+
from compas.geometry import Plane
7+
from compas.geometry import Point
8+
from compas.geometry import Polyline
9+
from compas.geometry import Vector
10+
from compas_viewer import Viewer
11+
from compas_viewer.config import Config
12+
from line_profiler import profile
13+
14+
from compas_cgal.slicer import slice_mesh
15+
16+
17+
@profile
18+
def main():
19+
# Get Mesh from STL
20+
FILE = Path(__file__).parent.parent.parent / "data" / "3DBenchy.stl"
21+
benchy = Mesh.from_stl(FILE)
22+
23+
V, F = benchy.to_vertices_and_faces()
24+
25+
# Get Slice planes from the bounding box
26+
bbox = benchy.aabb()
27+
normal = Vector(0, 0, 1)
28+
planes = []
29+
for i in np.linspace(bbox.zmin, bbox.zmax, 50):
30+
plane = Plane(Point(0, 0, i), normal)
31+
planes.append(plane)
32+
33+
# Slice
34+
slicer_polylines = slice_mesh((V, F), planes)
35+
36+
# Convert edges to polylines
37+
polylines = []
38+
for polyline in slicer_polylines:
39+
points = []
40+
for point in polyline:
41+
points.append(Point(*point))
42+
polylines.append(Polyline(points))
43+
44+
return benchy, polylines
45+
46+
47+
mesh, polylines = main()
48+
49+
# ==============================================================================
50+
# Visualize
51+
# ==============================================================================
52+
53+
config = Config()
54+
config.camera.target = [0, 100, 0]
55+
config.camera.position = [0, -75, 50]
56+
config.camera.scale = 10
57+
58+
viewer = Viewer(config=config)
59+
60+
viewer.scene.add(mesh, opacity=0.5, show_lines=False, show_points=False)
61+
for polyline in polylines:
62+
viewer.scene.add(polyline, linewidth=2, show_points=False)
63+
64+
viewer.show()

docs/examples/example_slicer.rst

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
Mesh Slicing
2+
============
3+
4+
This example demonstrates how to slice a mesh with multiple planes using COMPAS CGAL.
5+
6+
Key Features:
7+
8+
* Loading STL mesh files
9+
* Creating multiple slice planes from bounding box
10+
* Slicing mesh with multiple planes
11+
* Converting slice results to polylines
12+
* Visualization with semi-transparent mesh and slice curves
13+
14+
.. figure:: /_images/example_slicer.png
15+
:figclass: figure
16+
:class: figure-img img-fluid
17+
18+
.. literalinclude:: example_slicer.py
19+
:language: python

src/compas_cgal/skeletonization.py

Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
import numpy as np
2+
from compas.plugins import plugin
3+
4+
from compas_cgal import skeletonization_ext
5+
6+
from .types import PolylinesNumpySkeleton
7+
from .types import VerticesFaces
8+
9+
10+
@plugin(category="mesh")
11+
def mesh_skeleton(mesh: VerticesFaces) -> PolylinesNumpySkeleton:
12+
"""Compute the geometric skeleton of a triangle mesh using mean curvature flow.
13+
14+
Parameters
15+
----------
16+
mesh : VerticesFaces
17+
A tuple containing:
18+
* vertices: Nx3 array of vertex coordinates
19+
* faces: Mx3 array of vertex indices
20+
21+
Returns
22+
-------
23+
PolylinesNumpySkeleton
24+
List of polylines representing the skeleton edges.
25+
Each polyline is a tuple of start and end point coordinates.
26+
27+
Raises
28+
------
29+
TypeError
30+
If the input mesh is not a tuple of vertices and faces.
31+
ValueError
32+
If the vertices array is not Nx3.
33+
If the faces array is not Mx3.
34+
If the face indices are out of range.
35+
If the mesh is not manifold and closed.
36+
RuntimeError
37+
If the mesh contraction fails to converge.
38+
39+
Notes
40+
-----
41+
The input mesh must be manifold and closed.
42+
The skeleton is computed using mean curvature flow.
43+
"""
44+
V, F = mesh
45+
V_numpy = np.asarray(V, dtype=np.float64, order="C") # Ensure C-contiguous
46+
F_numpy = np.asarray(F, dtype=np.int32, order="C") # Ensure C-contiguous
47+
48+
# Get start and end points as flattened vectorS
49+
start_points, end_points = skeletonization_ext.mesh_skeleton(V_numpy, F_numpy)
50+
51+
# Convert flattened vectors to list of point coordinates
52+
edges = []
53+
for i in range(0, len(start_points), 3):
54+
start = [start_points[i], start_points[i + 1], start_points[i + 2]]
55+
end = [end_points[i], end_points[i + 1], end_points[i + 2]]
56+
edges.append((start, end))
57+
58+
return edges

src/compas_cgal/slicer.py

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
import numpy as np
2+
from compas.geometry import Plane
3+
from compas.plugins import plugin
4+
5+
from compas_cgal import slicer_ext
6+
7+
from .types import PolylinesNumpy
8+
from .types import VerticesFaces
9+
10+
11+
@plugin(category="trimesh", pluggable_name="trimesh_slice")
12+
def slice_mesh_planes(mesh: VerticesFaces, planes: list[Plane]) -> PolylinesNumpy:
13+
"""Slice a mesh by a list of planes.
14+
15+
Parameters
16+
----------
17+
mesh : :attr:`compas_cgal.types.VerticesFaces`
18+
The mesh to slice.
19+
planes : :attr:`compas_cgal.types.Planes`
20+
The slicing planes.
21+
22+
Returns
23+
-------
24+
:attr:`compas_cgal.types.PolylinesNumpy`
25+
A list of slice polylines, with each polyline an array of points.
26+
27+
Examples
28+
--------
29+
>>> from compas.geometry import Sphere, Plane, Polyline
30+
>>> from compas.itertools import linspace
31+
>>> from compas_cgal.slicer import slice_mesh
32+
33+
>>> sphere = Sphere(1.0, point=[0, 0, 1.0])
34+
>>> mesh = sphere.to_vertices_and_faces(u=32, v=32, triangulated=True)
35+
36+
>>> planes = [Plane([0, 0, z], [0, 0, 1.0]) for z in linspace(0.1, 1.9, 19)]
37+
38+
>>> result = slice_mesh(mesh, planes)
39+
>>> polylines = [Polyline(points) for points in result]
40+
41+
"""
42+
vertices, faces = mesh
43+
points, normals = zip(*planes)
44+
V = np.asarray(vertices, dtype=np.float64, order="C")
45+
F = np.asarray(faces, dtype=np.int32, order="C")
46+
P = np.array(points, dtype=np.float64, order="C")
47+
N = np.array(normals, dtype=np.float64, order="C")
48+
49+
pointsets = slicer_ext.slice_mesh(V, F, P, N)
50+
return pointsets
51+
52+
53+
slice_mesh = slice_mesh_planes

src/skeletonization.cpp

Lines changed: 60 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
#include "skeletonization.h"
2+
3+
typedef CGAL::Mean_curvature_flow_skeletonization<compas::Mesh> Skeletonization;
4+
typedef Skeletonization::Skeleton Skeleton;
5+
typedef boost::graph_traits<Skeleton>::vertex_descriptor SkeletonVertex;
6+
typedef boost::graph_traits<Skeleton>::edge_descriptor SkeletonEdge;
7+
8+
std::tuple<std::vector<double>, std::vector<double>>
9+
pmp_mesh_skeleton(
10+
Eigen::Ref<const compas::RowMatrixXd> vertices,
11+
Eigen::Ref<const compas::RowMatrixXi> faces)
12+
{
13+
compas::Mesh mesh = compas::mesh_from_vertices_and_faces(vertices, faces);
14+
15+
Skeleton skeleton;
16+
Skeletonization mcs(mesh);
17+
18+
mcs.contract_until_convergence();
19+
mcs.convert_to_skeleton(skeleton);
20+
21+
// Initialize vectors to store start and end points
22+
std::vector<double> start_points;
23+
std::vector<double> end_points;
24+
25+
// Reserve space for efficiency
26+
size_t num_edges = boost::num_edges(skeleton);
27+
start_points.reserve(num_edges * 3); // Each point has 3 coordinates
28+
end_points.reserve(num_edges * 3);
29+
30+
// Extract skeleton edges
31+
for (SkeletonEdge edge : CGAL::make_range(edges(skeleton))) {
32+
const compas::Kernel::Point_3& start = skeleton[source(edge, skeleton)].point;
33+
const compas::Kernel::Point_3& end = skeleton[target(edge, skeleton)].point;
34+
35+
// Add start point coordinates
36+
start_points.push_back(start.x());
37+
start_points.push_back(start.y());
38+
start_points.push_back(start.z());
39+
40+
// Add end point coordinates
41+
end_points.push_back(end.x());
42+
end_points.push_back(end.y());
43+
end_points.push_back(end.z());
44+
}
45+
46+
return std::make_tuple(start_points, end_points);
47+
};
48+
49+
NB_MODULE(skeletonization_ext, m) {
50+
51+
nb::bind_vector<std::vector<double>>(m, "VectorDouble");
52+
53+
m.def(
54+
"mesh_skeleton",
55+
&pmp_mesh_skeleton,
56+
"Create a geometric skeleton from a mesh using mean curvature flow",
57+
"vertices"_a,
58+
"faces"_a
59+
);
60+
}

src/skeletonization.h

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
#pragma once
2+
3+
#include "compas.h"
4+
5+
// CGAL skeletonization
6+
#include <CGAL/Mean_curvature_flow_skeletonization.h>
7+
#include <CGAL/boost/graph/split_graph_into_polylines.h>
8+
9+
/**
10+
* @brief Compute the geometric skeleton of a triangle mesh using mean curvature flow.
11+
*
12+
* @param vertices Matrix of vertex positions as Nx3 matrix in row-major order (float64)
13+
* @param faces Matrix of face indices as Mx3 matrix in row-major order (int32)
14+
* @return std::tuple<std::vector<double>, std::vector<double>> containing:
15+
* - Start points of skeleton edges as vector of 3D coordinates (float64)
16+
* - End points of skeleton edges as vector of 3D coordinates (float64)
17+
*/
18+
std::tuple<std::vector<double>, std::vector<double>>
19+
pmp_mesh_skeleton(
20+
Eigen::Ref<const compas::RowMatrixXd> vertices,
21+
Eigen::Ref<const compas::RowMatrixXi> faces);

0 commit comments

Comments
 (0)