At its core, trueform is a collection of geometric primitives that view your data, and ranges of these primitives. The primitives and their ranges can be injected with additional semantics through a composable policy system.
primitive<Dims, Policy> → ... → primitive<Dims, Policy_n>
↓
primitive_range<Dims, Policy0> → ... → primitive_range<Dims, Policy_n>
↓
form<Dims, Policy>
↑ ↑
tree frame ← transformation
↑
inverse_transformation
Include the module with:
#include <trueform/core.hpp>
Extract coordinate type and dimensions from any policy:
// Extract coordinate type from any policy
using common_t = tf::coordinate_type_t<Policy0, Policy1>;
common_t scalar = 2.0;
// Extract coordinate dimensions
constexpr std::size_t dims = tf::coordinate_dims_v<Policy>;
// These work with any primitive or primitive range
tf::point<float, 3> pt;
static_assert(tf::coordinate_dims_v<decltype(pt)> == 3);
using coord_t = tf::coordinate_type_t<decltype(pt)>; // float
primitive<std::size_t(Dims), Policy>. The Policy parameter defines the primitive's behavior and enables extensions.Three main variations are provided:
| Concept | General Template | Owning Alias | View Alias |
|---|---|---|---|
| Vector | tf::vector_like<Dims, Policy> | tf::vector<Type, Dims> | tf::vector_view<Type, Dims> |
| Unit Vector | tf::unit_vector_like<Dims, Policy> | tf::unit_vector<Type, Dims> | tf::unit_vector_view<Type, Dims> |
| Point | tf::point_like<Dims, Policy> | tf::point<Type, Dims> | tf::point_view<Type, Dims> |
// Vectors
tf::vector<float, 3> v0{1.f, 1.f, 1.f};
float buf[3]{2, 2, 2};
auto vview0 = tf::make_vector_view(buf);
auto vview1 = tf::make_vector_view<3>(&buf[0]);
// Unit vectors
tf::unit_vector<float, 3> uv0{v0};
auto uv1 = tf::make_unit_vector(v0);
auto uv2 = tf::make_unit_vector(vview0);
// This will not normalize
auto uv3 = tf::make_unit_vector(tf::unsafe, v0);
auto uv4 = tf::make_unit_vector_view(uv0);
// Points
tf::point<float, 3> pt0{{4, 4, 4}};
auto pview0 = tf::make_point_view(buf);
auto pview1 = tf::make_point_view<3>(&buf[0]);
They all support standard geometric algebra (the appropriate subset of operations +, -, *), conversions (.as<T>()), and essential functions like tf::dot and tf::cross.
pt + pt is nonsensical). If the full set is needed (such as computing a centroid), you may view the point_like as a vector_like using pt.as_vector_view().Lines and rays are a composite of a point origin and a vector direction.
| Concept | General Template | Owning Alias |
|---|---|---|
| Line | tf::line_like<Dims, Policy> | tf::line<Type, Dims> |
| Ray | tf::ray_like<Dims, Policy> | tf::ray<Type, Dims> |
auto line0 = tf::make_line_between_points(pt0, pt1);
auto line1 = tf::make_line_like(point_like, vector_like); // Creates view when inputs are views
auto ray0 = tf::make_ray_between_points(pt0, pt1);
// Support parametric evaluation
auto point_on_line = line0(2.5f); // origin + 2.5 * direction
make_line_like(point_like, vector_like) will produce a view when the inputs are views. The factory make_line always returns an owning alias. The line_like is convertible to a line. The same holds true for rays.A plane is a composite of a unit_vector_like<Dims, Policy> normal and a tf::coordinate_type<Policy> d, where d is the negative dot product between the normal and a point in the plane.
| Concept | General Template | Owning Alias |
|---|---|---|
| plane | tf::plane_like<Dims, Policy> | tf::plane<Type, Dims> |
tf::point<float, 3> pt;
tf::unit_vector<float, 3> normal;
auto plane0 = tf::make_plane(pt, pt, pt);
auto plane1 = tf::make_plane(normal, pt);
auto plane2 = tf::make_plane(normal, -tf::dot(normal, pt));
auto plane3 = tf::make_plane_like(unit_vector_like, coordinate_type); // View when inputs are views
A tf::segment<Dims, Policy> is a wrapper around a policy that behaves as a range of tf::point_like, with compile-time size of 2.
// Creates copies of the two points
auto seg0 = tf::make_segment_between_points(pt0, pt1);
auto [seg0_pt0, seg0_pt1] = seg0;
std::array<tf::point<float, 3>, 2> r; // any range of two points
auto seg1 = tf::make_segment(r);
// With edges that index into a larger range of points
std::array<int, 2> ids{0, 1};
auto seg2 = tf::make_segment(ids, r);
// ids are a view, as are the points
auto [id0, id1] = seg2.indices();
auto [seg2_pt0, seg2_pt1] = seg2;
A tf::polygon<Dims, Policy> is a wrapper around a policy that behaves as a range of tf::point_like. When the policy has a static size, so does the polygon.
std::array<tf::point<float, 3>, 3> r;
auto polygon0 = tf::make_polygon(r);
// With faces that index into a larger range of points
std::array<int, 3> ids{0, 1, 2};
auto polygon1 = tf::make_polygon(ids, r);
// ids are a view, as are the points
auto [id0, id1, id2] = polygon1.indices();
auto [pt0, pt1, pt2] = polygon1;
tf::static_size internally to determine the static size of the range being passed into it. All tf ranges propagate this static information. We still offer an overload tf::make_polygon<V> where the user manually supplies this information.An axis-aligned-bounding-box is a composite of a point_like min and a point_like max, representing the minimal and maximal corners.
| Concept | General Template | Owning Alias |
|---|---|---|
| aabb | tf::aabb_like<Dims, Policy> | tf::aabb<Type, Dims> |
auto aabb0 = tf::make_aabb_like(min_point_like, max_point_like); // View when inputs are views
auto aabb1 = tf::make_aabb(min_point, max_point); // Always owning
// AABB of any finite primitive
tf::aabb<float, 3> aabb = tf::aabb_from(primitive);
// Additional methods
auto diag = aabb.diagonal();
auto center = aabb.center();
auto size = aabb.size();
A transformation consists of a rotation R and a translation t. It maps points and vectors:
| Type | Mapping |
|---|---|
point_like | R.dot(pt) + T |
vector_like | R.dot(vec) |
| Concept | General Template | Owning Alias | View Alias |
|---|---|---|---|
| transformation | tf::transformation_like<Dims, Policy> | tf::transformation<Type, Dims> | tf::transformation_view<Dims, Policy> |
tf::transformation_view<float, 3> tr_view{float_ptr};
tf::transformation<float, 3> tr{tr_view};
tr.fill(other_float_ptr);
// Convenience factories
auto identity = tf::make_identity_transformation<float, 3>();
auto translated = tf::make_transformation_from_translation(vector);
// Memory layout: Dims rows of Dims+1 columns
// Last element of each row is the translation for that dimension
A frame_like<Dims, Policy> is a composition of a transformation and its inverse:
| Concept | General Template | Owning Alias |
|---|---|---|
| frame | tf::frame_like<Dims, Policy> | tf::frame<Type, Dims> |
tf::frame<float, 3> frame0;
tf::frame<float, 3> frame1{tr_view};
// Safe policy ensures inverse is always computed after changes
frame.fill(float_ptr/*, ptr for inverse*/);
frame.set(transformation /*, inverse_transformation*/);
tf::frame uses a safe policy that ensures the inverse is always computed after changes. The general tf::frame_like offers no such guarantees, but is convertible to a tf::frame.Any primitive from the tf:: namespace can be transformed using tf::transformed(_this, _by_transformation):
auto tr0 = tf::random_transformation<float>();
auto tr1 = tf::random_transformation<float>();
auto tr1_dot_tr0 = tf::transformed(tr0, tr1);
// Transform any primitive
auto transformed_point = tf::transformed(pt, tr0);
auto transformed_polygon = tf::transformed(polygon, frame);
Primitives support distance, intersection, classification, and ray casting queries.
All pairs of primitives support the following queries:
| Query | Returns |
|---|---|
distance2 | Squared distance between primitives |
distance | Distance between primitives |
closest_metric_point | tf::metric_point (on left argument) |
closest_metric_point_pair | tf::metric_point_pair |
intersects | bool - do the primitives intersect |
// Squared distance (faster, avoids sqrt)
auto d2 = tf::distance2(point, polygon);
// Distance
auto d = tf::distance(segment0, segment1);
// Closest point on polygon to a point
auto metric_pt = tf::closest_metric_point(polygon, point);
auto [metric, closest_pt] = metric_pt;
// Closest points between two primitives
auto metric_pair = tf::closest_metric_point_pair(polygon0, polygon1);
auto [dist2, pt_on_poly0, pt_on_poly1] = metric_pair;
// Intersection test
bool do_intersect = tf::intersects(aabb0, aabb1);
Classify a point's position relative to a primitive, returning either tf::sidedness or tf::containment.
| Query | Returns | Dims |
|---|---|---|
classify(point, plane) | tf::sidedness | 3D |
classify(point, line) | tf::sidedness | 2D |
classify(point, ray) | tf::sidedness | 2D |
classify(point, segment) | tf::sidedness | 2D |
classify(point, polygon) | tf::containment | 2D, 3D |
Sidedness values:
on_positive_side - above the plane / right of the 2D primitiveon_negative_side - below the plane / left of the 2D primitiveon_boundary - on the plane / colinear with the primitiveContainment values:
inside - point is inside the polygonoutside - point is outside the polygonon_boundary - point lies on the polygon boundary// Point vs plane (2D or 3D)
auto side = tf::classify(point, plane);
if (side == tf::sidedness::on_positive_side) { /* above plane */ }
// Point vs 2D segment (which side of the line?)
auto side_2d = tf::classify(point_2d, segment_2d);
// Point vs polygon (inside/outside test)
auto cont = tf::classify(point, polygon);
if (cont != tf::containment::outside) { /* point inside or on boundary */ }
Ray casting tests whether a ray intersects a primitive, returning both the intersection status and the parametric distance t along the ray.
| Query | Returns |
|---|---|
ray_cast | tf::ray_cast_info (status, t) |
ray_hit | tf::ray_hit_info (status, t, point) |
Both return types are convertible to bool, returning true only when status == tf::intersect_status::intersection.
Supported primitives: point, line, ray, segment, plane, polygon, aabb, obb
Intersection status values:
intersection - valid intersection foundnone - no intersection (e.g., outside [min_t, max_t] range)parallel - ray and primitive are parallelcoplanar / colinear - ray lies within the primitiveauto seg = tf::make_segment_between_points(tf::random_point<float, 3>(),
tf::random_point<float, 3>());
auto ray = tf::make_ray_between_points(tf::random_point<float, 3>(),
tf::random_point<float, 3>());
// Configure parametric bounds [min_t, max_t] for valid intersections
auto config = tf::make_ray_config(0.f, 100.f);
// ray_cast: lightweight result (status + t only)
auto r_cast = tf::ray_cast(ray, seg, config);
if (r_cast) {
auto [status, t] = r_cast;
// t is the parametric distance: hit_point = ray.origin + t * ray.direction
}
// ray_hit: includes the intersection point
auto r_hit = tf::ray_hit(ray, seg, config);
if (r_hit) {
auto [status, t, point] = r_hit;
}
ray_cast when you only need to know if and where along the ray an intersection occurs. Use ray_hit when you also need the intersection point coordinates.The core philosophy of trueform is to work with views of your existing data. Every primitive_range is a template of the form primitive_range<std::size_t(Dims), Policy>.
trueform provides several range adaptors that preserve and propagate static size information, accessible via tf::static_size.
auto r0 = tf::make_range(your_container);
// If you know it has n-elements and this is not known to tf::static_size
auto r1 = tf::make_range<N>(your_container);
std::vector<int> raw_ids;
auto triangle_faces0 = tf::make_blocked_range<3>(raw_ids);
auto [t0id0, t0id1, t0id2] = triangle_faces0.front();
// Legacy VTK format (3, a, b, c, 3, e, f, g)
auto triangle_faces1 = tf::make_tag_blocked_range<3>(raw_ids);
auto [t1id0, t1id1, t1id2] = triangle_faces1.front();
// Segments
auto segments0 = tf::make_blocked_range<2>(raw_ids);
auto [s0id0, s0id1] = segments0.front();
// Sliding window for curve points
auto segments1 = tf::make_slide_range<2>(raw_ids);
auto [s1id0, s1id1] = segments1.front();
tf::make_blocked_range and other static variants have a defined value_type which enables them to be sortable. The value_type is a static array that holds a copy of the view's data.For variable-length blocks with offset arrays:
tf::buffer<int> offsets = {0, 3, 7, 10}; // Block boundaries
tf::buffer<int> data = {0,1,2, 3,4,5,6, 7,8,9}; // Packed data
auto blocks = tf::make_offset_block_range(offsets, data);
for (auto block : blocks) {
for (auto value : block) {
// Process value
}
}
For index-based access to data:
tf::buffer<int> indices = {2, 0, 3, 1};
tf::buffer<float> values = {10.0f, 20.0f, 30.0f, 40.0f};
auto indirect_view = tf::make_indirect_range(indices, values);
// indirect_view[0] == values[2] == 30.0f
// indirect_view[1] == values[0] == 10.0f
For applying index maps to block-structured data inline:
tf::buffer<std::array<int, 3>> faces = {{0,1,2}, {3,4,5}, {6,7,8}};
tf::index_map_buffer<int> face_map; // Maps old face IDs to new point IDs
// Fill face_map...
auto remapped_faces = tf::make_block_indirect_range(faces, face_map.f());
// Sequence range for indices
auto sequence = tf::make_sequence_range(100); // 0, 1, 2, ..., 99
// Enumeration
auto enumerated = tf::enumerate(data_range); // pairs of (index, value)
// Zip ranges together
auto zipped = tf::zip(range1, range2, range3);
// Take/drop operations
auto first_10 = tf::take(data_range, 10);
auto skip_5 = tf::drop(data_range, 5);
// Slice operations
auto slice = tf::slice(data_range, 5, 14); // Elements 5-14
// Constant range (for default values)
auto constant_values = tf::make_constant_range(default_value, count);
// Mapped range (transform on access)
auto mapped = tf::make_mapped_range(data_range, [](auto x) { return x * 2; });
| Concept | Template | Factory |
|---|---|---|
| vectors | vectors<Dims, Policy> | make_vectors |
| unit vectors | unit_vectors<Dims, Policy> | make_unit_vectors |
| points | points<Dims, Policy> | make_points |
// From flat ranges
std::vector<float> raw_pts;
auto pts = tf::make_points<3>(raw_pts);
tf::point_view<float, 3> pt = pts.front();
// From ranges of primitives
std::vector<tf::point<float, 3>> pts0;
auto pts = tf::make_points(pts0);
// Zero-copy view creation
float* coordinate_array = get_external_coords();
int point_count = get_point_count();
auto point_view = tf::make_points<3>(tf::make_range(coordinate_array, point_count * 3));
// Work with individual points
for (auto point : point_view) {
// point is a tf::point_view<float, 3>
float x = point[0];
float y = point[1];
float z = point[2];
}
points<Dims, Policy> provide an additional method .as_vector_view(), when one needs complete vector algebra over their points.Curves and embedded graphs are modeled by a range of segments:
| Concept | Template | Factory |
|---|---|---|
| segments | segments<Dims, Policy> | make_segments |
// From a sequence of edges
auto segments0 = tf::make_segments(tf::make_blocked_range<2>(edge_indices), points);
// From a sequence of points
auto segments1 = tf::make_segments(tf::make_slide_range<2>(point_indices), points);
// Using ids to index into a larger array of points
std::vector<int> ids;
auto segments2 = tf::make_segments(tf::make_blocked_range<2>(ids), points);
auto segments3 = tf::make_segments(tf::make_slide_range<2>(ids), points);
// Segment elements behave as expected
auto [s3pt0, s3pt1] = segments3.front();
auto [s3_id0, s3_id1] = segments3.front().indices();
// Additional methods
auto [s3_id0_, s3_id1_] = segments3.edges().front();
auto points_range = segments3.points();
Meshes are modeled by a range of polygons:
| Concept | Template | Factory |
|---|---|---|
| polygons | polygons<Dims, Policy> | make_polygons |
// From a sequence of points
auto polygons0 = tf::make_polygons(tf::make_blocked_range<3>(point_indices), points);
auto [p0pt0, p0pt1, p0pt2] = polygons0.front();
// Using ids to index into a larger array of points
std::vector<int> ids;
auto polygons1 = tf::make_polygons(tf::make_blocked_range<3>(ids), points);
// Legacy VTK format (3, a, b, c, 3, e, f, g)
auto polygons2 = tf::make_polygons(tf::make_tag_blocked_range<3>(ids), points);
// Polygon elements behave as expected
auto [p2pt0, p2pt1, p2pt2] = polygons2.front();
auto [p2_id0, p2_id1, p2_id2] = polygons2.front().indices();
// Additional methods
auto [p2_id0_, p2_id1_, p2_id2_] = polygons2.faces().front();
auto points_range = polygons2.points();
For meshes with variable vertex counts (mixed triangles, quads, n-gons), use tf::make_offset_block_range:
// Offsets define block boundaries, data contains vertex indices
tf::buffer<int> offsets = {0, 3, 7, 10}; // 3 polygons: tri, quad, tri
tf::buffer<int> data = {0,1,2, 3,4,5,6, 7,8,9};
auto polygons = tf::make_polygons(tf::make_offset_block_range(offsets, data), points);
// Iterate over variable-size polygons
for (auto polygon : polygons) {
for (auto pt : polygon) {
// Process each vertex
}
for (auto vertex_id : polygon.indices()) {
// Process vertex index
}
}
// or faces directly
for(auto face: polygons.faces());
tf::static_size_v == tf::dynamic_size. All algorithms work with both static and dynamic polygon ranges, with compile-time optimizations applied when the size is known statically.Semantic wrappers for edge and face data:
// Edges
tf::buffer<std::array<int, 2>> edge_data;
auto edges = tf::make_edges(edge_data);
tf::buffer<int> flat_edges;
auto edges_flat = tf::make_edges(tf::make_blocked_range<2>(flat_edges));
for (auto edge : edges) {
auto [v0, v1] = edge;
// Process edge vertices
}
// Faces
tf::buffer<std::array<int, 3>> face_data;
auto faces = tf::make_faces(face_data);
tf::buffer<int> flat_faces;
auto faces_flat = tf::make_faces(tf::make_blocked_range<3>(flat_faces));
for (auto face : faces) {
auto [v0, v1, v2] = face;
// Process face vertices
}
// Paths
tf::offset_block_buffer<int, int> path_data;
path_data.push_back({0, 1, 2, 3}); // First path
path_data.push_back({4, 5, 6}); // Second path
auto paths = tf::make_paths(path_data);
for (auto path : paths) {
for (auto vertex_id : path) {
// Process path vertices
}
}
// Curves combine paths with point data
tf::offset_block_buffer<int, int> path_indices;
tf::points_buffer<float, 3> curve_points;
// Fill data...
auto curves = tf::make_curves(path_indices, curve_points);
for (auto curve : curves) {
// Access both indices and geometry
for (auto vertex_id : curve.indices()) {
// Process vertex indices
}
for (auto point : curve) {
// Process geometric points
}
}
While views work with your existing data, trueform provides efficient data structures for managing and outputting geometric data. All buffers in trueform are flat and composed - you can always access the underlying memory pointers for efficient data transport.
tf::buffer<T> is a lightweight alternative to std::vector for POD types:
tf::buffer<float> coords;
coords.allocate(1000); // Allocates uninitialized memory
coords.push_back(1.0f);
coords.emplace_back(2.0f);
// Take ownership of underlying memory
std::size_t byte_size = coords.size() * sizeof(float);
float* raw_ptr = coords.release();
// Standard container interface
for (auto value : coords) {
// Process value
}
Key differences from std::vector:
allocate() and reallocate() provide uninitialized memorytf::blocked_buffer<T, BlockSize> manages fixed-size blocks of data:
tf::blocked_buffer<int, 3> triangle_indices;
triangle_indices.emplace_back(0, 1, 2);
triangle_indices.push_back({3, 4, 5});
// Access blocks
auto triangle = triangle_indices.front(); // Returns array-like object
auto [v0, v1, v2] = triangle;
// Access underlying flat memory
int* raw_data = triangle_indices.data_buffer().data();
std::size_t total_ints = triangle_indices.size() * 3;
tf::offset_block_buffer<Index, T> handles variable-length blocks:
tf::offset_block_buffer<int, int> polygon_indices;
polygon_indices.push_back({0, 1, 2}); // Triangle
polygon_indices.push_back({3, 4, 5, 6}); // Quad
// Iterate over variable-length blocks
for (auto polygon : polygon_indices) {
for (auto vertex_id : polygon) {
// Process vertex
}
}
// Access underlying flat data
auto& offsets = polygon_indices.offsets_buffer();
auto& data = polygon_indices.data_buffer();
All structured buffers provide both semantic access through range views and direct access to underlying flat memory.
tf::points_buffer<float, 3> points;
points.allocate(1000);
points.emplace_back(1.0f, 2.0f, 3.0f);
points.push_back(tf::make_point<3>(4.0f, 5.0f, 6.0f));
// Semantic access through range view
auto first_point = points.front();
auto points_view = points.points(); // a tf::points view
// Direct access to flat memory
float* coordinates = points.data_buffer().data();
std::size_t total_floats = points.size() * 3;
tf::vectors_buffer<float, 3> vectors;
vectors.allocate(500);
vectors.emplace_back(1.0f, 0.0f, 0.0f);
// Semantic access
auto first_vector = vectors.front();
auto vectors_view = vectors.vectors(); // a tf::vectors view
// Direct access to flat memory
float* vector_data = vectors.data_buffer().data();
tf::unit_vectors_buffer<float, 3> normals;
normals.allocate(1000);
normals.push_back(tf::make_unit_vector<3>(1.0f, 0.0f, 0.0f));
// Semantic access
auto normals_view = normals.unit_vectors();
auto first_normal = normals_view.front();
// Direct access to flat memory
float* normal_data = normals.data_buffer().data();
tf::segments_buffer<int, float, 3> segments;
segments.edges_buffer().emplace_back(0, 1);
segments.points_buffer().emplace_back(0.0f, 0.0f, 0.0f);
segments.points_buffer().emplace_back(1.0f, 0.0f, 0.0f);
// Semantic access
auto segments_view = segments.segments(); // Equivalent range view
auto first_segment = segments_view.front();
auto [pt0, pt1] = first_segment;
// Direct access to flat memory
int* edge_indices = segments.edges_buffer().data_buffer().data();
float* point_coords = segments.points_buffer().data_buffer().data();
// Static size (triangles) - faces buffer is a blocked buffer
tf::polygons_buffer<int, float, 3, 3> triangles;
triangles.faces_buffer().emplace_back(0, 1, 2);
// Dynamic size (mixed polygons) - faces buffer is an offset block buffer
tf::polygons_buffer<int, float, 3, tf::dynamic_size> mixed_polygons;
mixed_polygons.faces_buffer().push_back({0, 1, 2}); // Triangle
mixed_polygons.faces_buffer().push_back({3, 4, 5, 6}); // Quad
// Semantic access
auto polygons_view = mixed_polygons.polygons(); // Equivalent range view
auto mesh_points = mixed_polygons.points();
auto mesh_faces = mixed_polygons.faces();
// Direct access to flat memory
int* face_data = mixed_polygons.faces_buffer().data_buffer().data();
float* point_data = mixed_polygons.points_buffer().data_buffer().data();
tf::curves_buffer<int, float, 3> curves;
curves.paths_buffer().push_back({0, 1, 2});
// Semantic access
auto curves_view = curves.curves(); // Equivalent range view
auto curve_points = curves.points();
auto curve_paths = curves.paths();
// Direct access to flat memory
int* path_data = curves.paths_buffer().data_buffer().data();
float* point_data = curves.points_buffer().data_buffer().data();
tf::index_map<Range0, Range1> manages mapping between old and new indices:
tf::index_map_buffer<int> point_mapping;
point_mapping.f().allocate(original_size);
point_mapping.kept_ids().allocate(filtered_size);
// Use with reindexing operations
auto reindexed_data = tf::reindexed(original_data, point_mapping);
// Access underlying data
int* forward_map = point_mapping.f().data();
int* kept_indices = point_mapping.kept_ids().data();
The trueform policy system allows you to compositionally add semantic information and behavior to primitives and ranges. This is achieved through two main operations, tag and zip.
A policy operation maps an object to a new version with an enriched policy:
object_t<Policy>→object_t<new_policy<Policy>>
These operations are hierarchy-idempotent: applying the same policy twice has no additional effect, making them safe to use in generic code.
A tag applies a single piece of metadata to an entire object. We support tagging with an id, normal, plane, and state.
auto base_pt = tf::random_point<float, 3>();
auto point_normal = tf::normalized(tf::random_vector<float, 3>());
auto direction = tf::normalized(tf::random_vector<float, 3>());
std::array<float, 3> color;
auto point = base_pt
| tf::tag_id("point")
| tf::tag_normal(point_normal | tf::tag_id("normal"))
| tf::tag_state(direction, color);
// Still behaves like a point
point += tf::random_vector<float, 3>();
auto d2 = tf::distance2(point, tf::random_point<float, 3>());
// Transformations correctly handle the object and its policies
tf::frame<float, 3> frame = tf::random_transformation<float, 3>();
auto transformed_point = tf::transformed(point, frame);
const auto &id = transformed_point.id();
const auto &transformed_normal = transformed_point.normal();
const auto &transformed_normal_id = transformed_normal.id();
const auto &[transformed_direction, same_color] = transformed_point.state();
A zip operation applies per-element data to a primitive_range. It effectively "zips" a range of data with the range of primitives, so that each primitive gets its own corresponding piece of data.
We support zipping with ids, normals, and states on primitive ranges.
std::vector<float> raw_pts;
std::vector<float> raw_normals;
std::vector<std::string> ids;
std::vector<float> raw_direction;
std::vector<std::array<float, 3>> colors;
auto points =
tf::make_points<3>(raw_pts)
| tf::tag_id("enriched points")
| tf::zip_ids(ids)
| tf::zip_normals(tf::make_unit_vectors<3>(raw_normals))
| tf::zip_states(tf::make_unit_vectors<3>(raw_direction), colors);
const auto & [directions_, colors_] = points.states();
const auto &[direction_, color_] = points.states().front();
const auto &id_ = points.id();
const auto &ids_ = points.ids();
const auto &normals_ = points.normals();
// Points are still a tf::points<Policy> and behave like one
auto transformed_point = tf::transformed(points.front(), frame);
const auto &id = transformed_point.id();
const auto &transformed_normal = transformed_point.normal();
const auto &[transformed_direction, color_t] = transformed_point.state();
To remove all policies from an object:
auto plain_points = points | tf::plain();
The core module provides parallel algorithms that integrate with trueform's range and buffer systems.
// Basic parallel apply
tf::parallel_apply(points, [](auto&& pt) {
pt = tf::normalized(pt.as_vector());
});
// With zip for multiple ranges
tf::parallel_apply(tf::zip(range1, range2), [](auto pair) {
auto &&[elem1, elem2] = pair;
elem1 += elem2;
});
// With checked execution for verification
tf::parallel_apply(points, [](auto&& pt) {
pt = tf::normalized(pt.as_vector());
}, tf::checked);
tf::buffer<float> results;
results.allocate(input_range.size());
tf::parallel_transform(input_range, results, [](auto value) {
return value * value; // Square each element
});
// Basic parallel copy
tf::parallel_copy(source_range, destination_range);
// Blocked copy for structured data
tf::parallel_copy_blocked(blocked_source, blocked_destination);
// Copy with index mapping
tf::parallel_copy_by_map_with_nones(source, destination, index_map, sentinel_value);
tf::buffer<int> data;
data.allocate(1000);
// Fill with value
tf::parallel_fill(data, 42);
// Generate sequence
tf::parallel_iota(data, 0); // 0, 1, 2, 3, ...
// Replace values
tf::parallel_replace(data, old_value, new_value);
These algorithms create new data structures from input data, optimized for parallel execution and memory efficiency.
tf::generic_generate provides parallel generation of variable-length data with automatic thread-local state management:
// Generate boundary edges from faces
tf::blocked_buffer<int, 2> boundary_edges;
tf::generic_generate(tf::enumerate(faces), boundary_edges.data_buffer(),
[&](const auto& pair, auto& buffer) {
const auto& [face_id, face] = pair;
int size = face.size();
int prev = size - 1;
for (int i = 0; i < size; prev = i++) {
if (is_boundary_edge(face[prev], face[i])) {
buffer.push_back(face[prev]);
buffer.push_back(face[i]);
}
}
});
// Generate with thread-local state to avoid allocations
tf::buffer<int> result_data;
tf::generic_generate(input_range, result_data,
tf::small_vector<int, 10>{}, // Thread-local work buffer
[&](const auto& element, auto& output, auto& work_buffer) {
work_buffer.clear();
process_element(element, work_buffer);
for (auto value : work_buffer) {
output.push_back(value);
}
});
// Generate into multiple buffers simultaneously
auto buffers = std::tie(buffer_a, buffer_b, buffer_c);
tf::generic_generate(input_range, buffers,
[&](const auto& element, auto& outputs) {
auto& [out_a, out_b, out_c] = outputs;
if (condition_a(element)) out_a.push_back(process_a(element));
if (condition_b(element)) out_b.push_back(process_b(element));
if (condition_c(element)) out_c.push_back(process_c(element));
});
tf::generate_offset_blocks creates offset-block data structures efficiently:
// Build face adjacency
tf::buffer<int> adjacency_offsets;
tf::buffer<int> adjacency_data;
tf::generate_offset_blocks(tf::make_sequence_range(faces.size()),
adjacency_offsets, adjacency_data,
[&](int face_id, auto& buffer) {
for (auto neighbor_id : compute_face_neighbors(face_id)) {
buffer.push_back(neighbor_id);
}
});
// Or work directly with the offset block buffer
tf::offset_block_buffer<int, int> result;
tf::generate_offset_blocks(input_range, result, work_lambda);
tf::blocked_reduce provides efficient parallel reduction with custom aggregation logic:
// Build intersection points
tf::buffer<tf::intersect::simple_intersection<int>> intersections;
tf::buffer<tf::point<float, 3>> intersection_points;
tf::blocked_reduce(
tf::enumerate(polygons),
std::tie(intersections, intersection_points),
std::make_tuple(tf::buffer<tf::intersect::simple_intersection<int>>{},
tf::buffer<tf::point<float, 3>>{}),
[&](const auto& polygon_range, auto& local_result) {
auto& [local_intersections, local_points] = local_result;
for (const auto& [polygon_id, polygon] : polygon_range) {
compute_intersections(polygon, local_intersections, local_points);
}
},
[&](const auto& local_result, auto& global_result) {
auto& [local_intersections, local_points] = local_result;
auto& [global_intersections, global_points] = global_result;
// Aggregate local results into global buffers
auto old_size = global_intersections.size();
global_intersections.reallocate(old_size + local_intersections.size());
std::copy(local_intersections.begin(), local_intersections.end(),
global_intersections.begin() + old_size);
old_size = global_points.size();
global_points.reallocate(old_size + local_points.size());
std::copy(local_points.begin(), local_points.end(),
global_points.begin() + old_size);
});
tf::blocked_reduce_sequenced_aggregate ensures aggregation happens in sequential order, critical for operations where order matters:
// Build face adjacency per edge with ordered aggregation
tf::buffer<int> offsets;
tf::buffer<int> adjacency_data;
tf::blocked_reduce_sequenced_aggregate(
tf::enumerate(faces),
std::tie(offsets, adjacency_data),
std::make_pair(tf::buffer<int>{}, tf::buffer<int>{}),
[&](const auto& face_range, auto& local_result) {
auto& [local_offsets, local_data] = local_result;
for (const auto& [face_id, face] : face_range) {
for (int i = 0; i < face.size(); ++i) {
local_offsets.push_back(local_data.size());
add_edge_neighbors(face_id, face[i], face[(i+1) % face.size()],
local_data);
}
}
},
[&](const auto& local_result, auto& global_result) {
auto& [local_offsets, local_data] = local_result;
auto& [global_offsets, global_data] = global_result;
// Sequential aggregation preserves order
auto old_data_size = global_data.size();
global_data.reallocate(old_data_size + local_data.size());
std::copy(local_data.begin(), local_data.end(),
global_data.begin() + old_data_size);
auto old_offsets_size = global_offsets.size();
global_offsets.reallocate(old_offsets_size + local_offsets.size());
auto it = global_offsets.begin() + old_offsets_size;
for (auto local_offset : local_offsets) {
*it++ = local_offset + old_data_size;
}
});
// Sequential aggregation ensures offset consistency
offsets.push_back(adjacency_data.size());