Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--release/scripts/startup/bl_ui/space_view3d.py2
-rw-r--r--source/blender/editors/sculpt_paint/curves_sculpt_comb.cc95
-rw-r--r--source/blender/editors/sculpt_paint/curves_sculpt_pinch.cc76
-rw-r--r--source/blender/editors/sculpt_paint/curves_sculpt_puff.cc68
-rw-r--r--source/blender/geometry/CMakeLists.txt17
-rw-r--r--source/blender/geometry/GEO_constraint_solver.hh194
-rw-r--r--source/blender/geometry/intern/constraint_solver.cc456
-rw-r--r--source/blender/geometry/tests/GEO_constraint_solver_test.cc85
-rw-r--r--source/blender/geometry/tests/performance/CMakeLists.txt11
-rw-r--r--source/blender/geometry/tests/performance/GEO_constraint_solver_performance_test.cc359
-rw-r--r--source/blender/makesdna/DNA_curves_types.h1
-rw-r--r--source/blender/makesrna/intern/rna_curves.c7
12 files changed, 1232 insertions, 139 deletions
diff --git a/release/scripts/startup/bl_ui/space_view3d.py b/release/scripts/startup/bl_ui/space_view3d.py
index 2f9050ba638..7f81a6d3129 100644
--- a/release/scripts/startup/bl_ui/space_view3d.py
+++ b/release/scripts/startup/bl_ui/space_view3d.py
@@ -156,6 +156,8 @@ class VIEW3D_HT_tool_header(Header):
sub.prop(context.object.data, "use_mirror_y", text="Y", toggle=True)
sub.prop(context.object.data, "use_mirror_z", text="Z", toggle=True)
+ layout.prop(context.object.data, "use_sculpt_collision", icon='MOD_PHYSICS', icon_only=True, toggle=True)
+
# Expand panels from the side-bar as popovers.
popover_kw = {"space_type": 'VIEW_3D', "region_type": 'UI', "category": "Tool"}
diff --git a/source/blender/editors/sculpt_paint/curves_sculpt_comb.cc b/source/blender/editors/sculpt_paint/curves_sculpt_comb.cc
index 52f2ddc6550..1b3b86daa0e 100644
--- a/source/blender/editors/sculpt_paint/curves_sculpt_comb.cc
+++ b/source/blender/editors/sculpt_paint/curves_sculpt_comb.cc
@@ -38,6 +38,8 @@
#include "ED_screen.h"
#include "ED_view3d.h"
+#include "GEO_constraint_solver.hh"
+
#include "UI_interface.h"
#include "WM_api.h"
@@ -53,6 +55,7 @@
namespace blender::ed::sculpt_paint {
using blender::bke::CurvesGeometry;
+using geometry::ConstraintSolver;
using threading::EnumerableThreadSpecific;
/**
@@ -66,8 +69,8 @@ class CombOperation : public CurvesSculptStrokeOperation {
/** Only used when a 3D brush is used. */
CurvesBrush3D brush_3d_;
- /** Length of each segment indexed by the index of the first point in the segment. */
- Array<float> segment_lengths_cu_;
+ /** Solver for length and contact constraints. */
+ ConstraintSolver constraint_solver_;
friend struct CombOperationExecutor;
@@ -98,6 +101,7 @@ struct CombOperationExecutor {
VArray<float> point_factors_;
Vector<int64_t> selected_curve_indices_;
IndexMask curve_selection_;
+ Array<float3> start_positions_;
float2 brush_pos_prev_re_;
float2 brush_pos_re_;
@@ -143,12 +147,18 @@ struct CombOperationExecutor {
if (falloff_shape_ == PAINT_FALLOFF_SHAPE_SPHERE) {
this->initialize_spherical_brush_reference_point();
}
- this->initialize_segment_lengths();
+
+ ConstraintSolver::Params params;
+ params.use_collision_constraints = curves_id_orig_->flag & CV_SCULPT_COLLISION_ENABLED;
+ self_->constraint_solver_.initialize(params, *curves_orig_, curve_selection_);
+
/* Combing does nothing when there is no mouse movement, so return directly. */
return;
}
- EnumerableThreadSpecific<Vector<int>> changed_curves;
+ start_positions_ = curves_orig_->positions();
+
+ EnumerableThreadSpecific<Vector<int64_t>> changed_curves;
if (falloff_shape_ == PAINT_FALLOFF_SHAPE_TUBE) {
this->comb_projected_with_symmetry(changed_curves);
@@ -160,7 +170,25 @@ struct CombOperationExecutor {
BLI_assert_unreachable();
}
- this->restore_segment_lengths(changed_curves);
+ const Mesh *surface = curves_id_orig_->surface && curves_id_orig_->surface->type == OB_MESH ?
+ static_cast<Mesh *>(curves_id_orig_->surface->data) :
+ nullptr;
+
+ /* Combine TLS curves into a single array for redistributing thread load.
+ * Brush filtering results in TLS lists with potentially very uneven sizes. */
+ int totcurves = 0;
+ for (auto curves : changed_curves) {
+ totcurves += curves.size();
+ }
+ Array<int64_t> all_changed_curves(totcurves);
+ totcurves = 0;
+ for (auto curves : changed_curves) {
+ all_changed_curves.as_mutable_span().slice(totcurves, curves.size()).copy_from(curves);
+ totcurves += curves.size();
+ };
+
+ self_->constraint_solver_.step_curves(
+ *curves_orig_, surface, transforms_, start_positions_, IndexMask(all_changed_curves));
curves_orig_->tag_positions_changed();
DEG_id_tag_update(&curves_id_orig_->id, ID_RECALC_GEOMETRY);
@@ -171,7 +199,7 @@ struct CombOperationExecutor {
/**
* Do combing in screen space.
*/
- void comb_projected_with_symmetry(EnumerableThreadSpecific<Vector<int>> &r_changed_curves)
+ void comb_projected_with_symmetry(EnumerableThreadSpecific<Vector<int64_t>> &r_changed_curves)
{
const Vector<float4x4> symmetry_brush_transforms = get_symmetry_brush_transforms(
eCurvesSymmetryType(curves_id_orig_->symmetry));
@@ -180,7 +208,7 @@ struct CombOperationExecutor {
}
}
- void comb_projected(EnumerableThreadSpecific<Vector<int>> &r_changed_curves,
+ void comb_projected(EnumerableThreadSpecific<Vector<int64_t>> &r_changed_curves,
const float4x4 &brush_transform)
{
const float4x4 brush_transform_inv = brush_transform.inverted();
@@ -196,7 +224,7 @@ struct CombOperationExecutor {
const float brush_radius_sq_re = pow2f(brush_radius_re);
threading::parallel_for(curve_selection_.index_range(), 256, [&](const IndexRange range) {
- Vector<int> &local_changed_curves = r_changed_curves.local();
+ Vector<int64_t> &local_changed_curves = r_changed_curves.local();
for (const int curve_i : curve_selection_.slice(range)) {
bool curve_changed = false;
const IndexRange points = curves_orig_->points_for_curve(curve_i);
@@ -252,7 +280,7 @@ struct CombOperationExecutor {
/**
* Do combing in 3D space.
*/
- void comb_spherical_with_symmetry(EnumerableThreadSpecific<Vector<int>> &r_changed_curves)
+ void comb_spherical_with_symmetry(EnumerableThreadSpecific<Vector<int64_t>> &r_changed_curves)
{
float4x4 projection;
ED_view3d_ob_project_mat_get(ctx_.rv3d, curves_ob_orig_, projection.values);
@@ -283,7 +311,7 @@ struct CombOperationExecutor {
}
}
- void comb_spherical(EnumerableThreadSpecific<Vector<int>> &r_changed_curves,
+ void comb_spherical(EnumerableThreadSpecific<Vector<int64_t>> &r_changed_curves,
const float3 &brush_start_cu,
const float3 &brush_end_cu,
const float brush_radius_cu)
@@ -296,7 +324,7 @@ struct CombOperationExecutor {
bke::crazyspace::get_evaluated_curves_deformation(*ctx_.depsgraph, *curves_ob_orig_);
threading::parallel_for(curve_selection_.index_range(), 256, [&](const IndexRange range) {
- Vector<int> &local_changed_curves = r_changed_curves.local();
+ Vector<int64_t> &local_changed_curves = r_changed_curves.local();
for (const int curve_i : curve_selection_.slice(range)) {
bool curve_changed = false;
const IndexRange points = curves_orig_->points_for_curve(curve_i);
@@ -350,51 +378,6 @@ struct CombOperationExecutor {
self_->brush_3d_ = *brush_3d;
}
}
-
- /**
- * Remember the initial length of all curve segments. This allows restoring the length after
- * combing.
- */
- void initialize_segment_lengths()
- {
- const Span<float3> positions_cu = curves_orig_->positions();
- self_->segment_lengths_cu_.reinitialize(curves_orig_->points_num());
- threading::parallel_for(curves_orig_->curves_range(), 128, [&](const IndexRange range) {
- for (const int curve_i : range) {
- const IndexRange points = curves_orig_->points_for_curve(curve_i);
- for (const int point_i : points.drop_back(1)) {
- const float3 &p1_cu = positions_cu[point_i];
- const float3 &p2_cu = positions_cu[point_i + 1];
- const float length_cu = math::distance(p1_cu, p2_cu);
- self_->segment_lengths_cu_[point_i] = length_cu;
- }
- }
- });
- }
-
- /**
- * Restore previously stored length for each segment in the changed curves.
- */
- void restore_segment_lengths(EnumerableThreadSpecific<Vector<int>> &changed_curves)
- {
- const Span<float> expected_lengths_cu = self_->segment_lengths_cu_;
- MutableSpan<float3> positions_cu = curves_orig_->positions_for_write();
-
- threading::parallel_for_each(changed_curves, [&](const Vector<int> &changed_curves) {
- threading::parallel_for(changed_curves.index_range(), 256, [&](const IndexRange range) {
- for (const int curve_i : changed_curves.as_span().slice(range)) {
- const IndexRange points = curves_orig_->points_for_curve(curve_i);
- for (const int segment_i : points.drop_back(1)) {
- const float3 &p1_cu = positions_cu[segment_i];
- float3 &p2_cu = positions_cu[segment_i + 1];
- const float3 direction = math::normalize(p2_cu - p1_cu);
- const float expected_length_cu = expected_lengths_cu[segment_i];
- p2_cu = p1_cu + direction * expected_length_cu;
- }
- }
- });
- });
- }
};
void CombOperation::on_stroke_extended(const bContext &C, const StrokeExtension &stroke_extension)
diff --git a/source/blender/editors/sculpt_paint/curves_sculpt_pinch.cc b/source/blender/editors/sculpt_paint/curves_sculpt_pinch.cc
index 3e43b1a6361..cc4cb619b7c 100644
--- a/source/blender/editors/sculpt_paint/curves_sculpt_pinch.cc
+++ b/source/blender/editors/sculpt_paint/curves_sculpt_pinch.cc
@@ -23,6 +23,8 @@
#include "DNA_screen_types.h"
#include "DNA_space_types.h"
+#include "GEO_constraint_solver.hh"
+
#include "ED_screen.h"
#include "ED_view3d.h"
@@ -38,10 +40,14 @@
namespace blender::ed::sculpt_paint {
+using geometry::ConstraintSolver;
+
class PinchOperation : public CurvesSculptStrokeOperation {
private:
bool invert_pinch_;
- Array<float> segment_lengths_cu_;
+
+ /** Solver for length and contact constraints. */
+ ConstraintSolver constraint_solver_;
/** Only used when a 3D brush is used. */
CurvesBrush3D brush_3d_;
@@ -67,6 +73,7 @@ struct PinchOperationExecutor {
VArray<float> point_factors_;
Vector<int64_t> selected_curve_indices_;
IndexMask curve_selection_;
+ Array<float3> start_positions_;
CurvesSurfaceTransforms transforms_;
@@ -113,8 +120,6 @@ struct PinchOperationExecutor {
brush_->falloff_shape);
if (stroke_extension.is_first) {
- this->initialize_segment_lengths();
-
if (falloff_shape == PAINT_FALLOFF_SHAPE_SPHERE) {
self_->brush_3d_ = *sample_curves_3d_brush(*ctx_.depsgraph,
*ctx_.region,
@@ -124,8 +129,14 @@ struct PinchOperationExecutor {
brush_pos_re_,
brush_radius_base_re_);
}
+
+ ConstraintSolver::Params params;
+ params.use_collision_constraints = curves_id_->flag & CV_SCULPT_COLLISION_ENABLED;
+ self_->constraint_solver_.initialize(params, *curves_, curve_selection_);
}
+ start_positions_ = curves_->positions();
+
Array<bool> changed_curves(curves_->curves_num(), false);
if (falloff_shape == PAINT_FALLOFF_SHAPE_TUBE) {
this->pinch_projected_with_symmetry(changed_curves);
@@ -137,7 +148,25 @@ struct PinchOperationExecutor {
BLI_assert_unreachable();
}
- this->restore_segment_lengths(changed_curves);
+ /* XXX Dumb array conversion to pass to the constraint solver.
+ * Should become unnecessary once brushes use the same methods for computing weights */
+ Vector<int64_t> changed_curves_indices;
+ changed_curves_indices.reserve(curves_->curves_num());
+ for (int64_t curve_i : changed_curves.index_range()) {
+ if (changed_curves[curve_i]) {
+ changed_curves_indices.append(curve_i);
+ }
+ }
+
+ const Mesh *surface = curves_id_->surface && curves_id_->surface->type == OB_MESH ?
+ static_cast<Mesh *>(curves_id_->surface->data) :
+ nullptr;
+ self_->constraint_solver_.step_curves(*curves_,
+ surface,
+ transforms_,
+ start_positions_,
+ IndexMask(changed_curves_indices));
+
curves_->tag_positions_changed();
DEG_id_tag_update(&curves_id_->id, ID_RECALC_GEOMETRY);
WM_main_add_notifier(NC_GEOM | ND_DATA, &curves_id_->id);
@@ -264,45 +293,6 @@ struct PinchOperationExecutor {
}
});
}
-
- void initialize_segment_lengths()
- {
- const Span<float3> positions_cu = curves_->positions();
- self_->segment_lengths_cu_.reinitialize(curves_->points_num());
- threading::parallel_for(curve_selection_.index_range(), 256, [&](const IndexRange range) {
- for (const int curve_i : curve_selection_.slice(range)) {
- const IndexRange points = curves_->points_for_curve(curve_i);
- for (const int point_i : points.drop_back(1)) {
- const float3 &p1_cu = positions_cu[point_i];
- const float3 &p2_cu = positions_cu[point_i + 1];
- const float length_cu = math::distance(p1_cu, p2_cu);
- self_->segment_lengths_cu_[point_i] = length_cu;
- }
- }
- });
- }
-
- void restore_segment_lengths(const Span<bool> changed_curves)
- {
- const Span<float> expected_lengths_cu = self_->segment_lengths_cu_;
- MutableSpan<float3> positions_cu = curves_->positions_for_write();
-
- threading::parallel_for(changed_curves.index_range(), 256, [&](const IndexRange range) {
- for (const int curve_i : range) {
- if (!changed_curves[curve_i]) {
- continue;
- }
- const IndexRange points = curves_->points_for_curve(curve_i);
- for (const int segment_i : IndexRange(points.size() - 1)) {
- const float3 &p1_cu = positions_cu[points[segment_i]];
- float3 &p2_cu = positions_cu[points[segment_i] + 1];
- const float3 direction = math::normalize(p2_cu - p1_cu);
- const float expected_length_cu = expected_lengths_cu[points[segment_i]];
- p2_cu = p1_cu + direction * expected_length_cu;
- }
- }
- });
- }
};
void PinchOperation::on_stroke_extended(const bContext &C, const StrokeExtension &stroke_extension)
diff --git a/source/blender/editors/sculpt_paint/curves_sculpt_puff.cc b/source/blender/editors/sculpt_paint/curves_sculpt_puff.cc
index 139e0d67e89..a6aeae58650 100644
--- a/source/blender/editors/sculpt_paint/curves_sculpt_puff.cc
+++ b/source/blender/editors/sculpt_paint/curves_sculpt_puff.cc
@@ -22,18 +22,21 @@
#include "BLI_length_parameterize.hh"
#include "GEO_add_curves_on_mesh.hh"
+#include "GEO_constraint_solver.hh"
#include "curves_sculpt_intern.hh"
namespace blender::ed::sculpt_paint {
+using geometry::ConstraintSolver;
+
class PuffOperation : public CurvesSculptStrokeOperation {
private:
/** Only used when a 3D brush is used. */
CurvesBrush3D brush_3d_;
- /** Length of each segment indexed by the index of the first point in the segment. */
- Array<float> segment_lengths_cu_;
+ /** Solver for length and contact constraints. */
+ ConstraintSolver constraint_solver_;
friend struct PuffOperationExecutor;
@@ -56,6 +59,7 @@ struct PuffOperationExecutor {
VArray<float> point_factors_;
Vector<int64_t> selected_curve_indices_;
IndexMask curve_selection_;
+ Array<float3> start_positions_;
const CurvesSculpt *curves_sculpt_ = nullptr;
const Brush *brush_ = nullptr;
@@ -124,7 +128,6 @@ struct PuffOperationExecutor {
BKE_mesh_runtime_looptri_len(surface_)};
if (stroke_extension.is_first) {
- this->initialize_segment_lengths();
if (falloff_shape_ == PAINT_FALLOFF_SHAPE_SPHERE) {
self.brush_3d_ = *sample_curves_3d_brush(*ctx_.depsgraph,
*ctx_.region,
@@ -134,8 +137,14 @@ struct PuffOperationExecutor {
brush_pos_re_,
brush_radius_base_re_);
}
+
+ ConstraintSolver::Params params;
+ params.use_collision_constraints = curves_id_->flag & CV_SCULPT_COLLISION_ENABLED;
+ self_->constraint_solver_.initialize(params, *curves_, curve_selection_);
}
+ start_positions_ = curves_->positions();
+
Array<float> curve_weights(curve_selection_.size(), 0.0f);
if (falloff_shape_ == PAINT_FALLOFF_SHAPE_TUBE) {
@@ -149,7 +158,22 @@ struct PuffOperationExecutor {
}
this->puff(curve_weights);
- this->restore_segment_lengths();
+
+ /* XXX Dumb array conversion to pass to the constraint solver.
+ * Should become unnecessary once brushes use the same methods for computing weights */
+ Vector<int64_t> changed_curves_indices;
+ changed_curves_indices.reserve(curve_selection_.size());
+ for (int64_t select_i : curve_selection_.index_range()) {
+ if (curve_weights[select_i] > 0.0f) {
+ changed_curves_indices.append(curve_selection_[select_i]);
+ }
+ }
+
+ self_->constraint_solver_.step_curves(*curves_,
+ surface_,
+ transforms_,
+ start_positions_,
+ IndexMask(changed_curves_indices));
curves_->tag_positions_changed();
DEG_id_tag_update(&curves_id_->id, ID_RECALC_GEOMETRY);
@@ -330,42 +354,6 @@ struct PuffOperationExecutor {
}
});
}
-
- void initialize_segment_lengths()
- {
- const Span<float3> positions_cu = curves_->positions();
- self_->segment_lengths_cu_.reinitialize(curves_->points_num());
- threading::parallel_for(curves_->curves_range(), 128, [&](const IndexRange range) {
- for (const int curve_i : range) {
- const IndexRange points = curves_->points_for_curve(curve_i);
- for (const int point_i : points.drop_back(1)) {
- const float3 &p1_cu = positions_cu[point_i];
- const float3 &p2_cu = positions_cu[point_i + 1];
- const float length_cu = math::distance(p1_cu, p2_cu);
- self_->segment_lengths_cu_[point_i] = length_cu;
- }
- }
- });
- }
-
- void restore_segment_lengths()
- {
- const Span<float> expected_lengths_cu = self_->segment_lengths_cu_;
- MutableSpan<float3> positions_cu = curves_->positions_for_write();
-
- threading::parallel_for(curves_->curves_range(), 256, [&](const IndexRange range) {
- for (const int curve_i : range) {
- const IndexRange points = curves_->points_for_curve(curve_i);
- for (const int segment_i : points.drop_back(1)) {
- const float3 &p1_cu = positions_cu[segment_i];
- float3 &p2_cu = positions_cu[segment_i + 1];
- const float3 direction = math::normalize(p2_cu - p1_cu);
- const float expected_length_cu = expected_lengths_cu[segment_i];
- p2_cu = p1_cu + direction * expected_length_cu;
- }
- }
- });
- }
};
void PuffOperation::on_stroke_extended(const bContext &C, const StrokeExtension &stroke_extension)
diff --git a/source/blender/geometry/CMakeLists.txt b/source/blender/geometry/CMakeLists.txt
index da83d9e8957..f5fd22b6cc5 100644
--- a/source/blender/geometry/CMakeLists.txt
+++ b/source/blender/geometry/CMakeLists.txt
@@ -16,6 +16,7 @@ set(INC
set(SRC
intern/add_curves_on_mesh.cc
+ intern/constraint_solver.cc
intern/fillet_curves.cc
intern/mesh_merge_by_distance.cc
intern/mesh_primitive_cuboid.cc
@@ -30,6 +31,7 @@ set(SRC
intern/uv_parametrizer.c
GEO_add_curves_on_mesh.hh
+ GEO_constraint_solver.hh
GEO_fillet_curves.hh
GEO_mesh_merge_by_distance.hh
GEO_mesh_primitive_cuboid.hh
@@ -76,3 +78,18 @@ if(WITH_TBB)
endif()
blender_add_lib(bf_geometry "${SRC}" "${INC}" "${INC_SYS}" "${LIB}")
+
+if(WITH_GTESTS)
+ set(TEST_SRC
+ tests/GEO_constraint_solver_test.cc
+ )
+ set(TEST_INC
+ )
+ set(TEST_LIB
+ bf_geometry
+ )
+ include(GTestTesting)
+ blender_add_test_executable(geometry "${TEST_SRC}" "${INC};${TEST_INC}" "${INC_SYS}" "${LIB};${TEST_LIB}")
+
+ add_subdirectory(tests/performance)
+endif()
diff --git a/source/blender/geometry/GEO_constraint_solver.hh b/source/blender/geometry/GEO_constraint_solver.hh
new file mode 100644
index 00000000000..3371909209a
--- /dev/null
+++ b/source/blender/geometry/GEO_constraint_solver.hh
@@ -0,0 +1,194 @@
+/* SPDX-License-Identifier: GPL-2.0-or-later */
+
+#pragma once
+
+#include "BKE_bvhutils.h"
+#include "BKE_curves.hh"
+
+/** \file
+ * \ingroup geo
+ * \brief Constraint solver for curve deformations.
+ */
+
+namespace blender::geometry {
+
+class ConstraintSolver {
+ public:
+ enum SolverType {
+ /* A fast single-iteration solver that solves constraints sequentially
+ * from the root down (Follow-the-Leader, FTL).
+ * The result is not physically correct, but very fast to compute.
+ * This solver type is suitable for editing, but not so much for accurate
+ * physical simulations, since the root side of a curve is infinitely stiff.
+ *
+ * For details see "Fast Simulation of Inextensible Hair and Fur"
+ * by Matthias Mueller and Tae Yong Kim. */
+ Sequential,
+ /* Position Based Dynamics (PBD) solves constraints based on relative mass.
+ * The solver requires multiple iterations per step. This is generally slower
+ * than the FTL method, but leads to physically correct movement.
+ *
+ * Based on "XPBD: Position-Based Simulation of Compliant Constrained Dynamics" */
+ PositionBasedDynamics,
+ };
+
+ struct Params {
+ SolverType solver_type = SolverType::Sequential;
+
+ /* Keep the distance between points constant. */
+ bool use_length_constraints = true;
+ /* Root point is fixed to the surface. */
+ bool use_root_constraints = true;
+ /* Points do not penetrate the surface. */
+ bool use_collision_constraints = true;
+
+ /* Compliance (inverse stiffness)
+ * Alpha is used in physical simulation to control the softness of a constraint:
+ * For alpha == 0 the constraint is stiff and the maximum correction factor is applied.
+ * For values > 0 the constraint becomes squishy, and some violation is
+ * permitted, and the constraint gets corrected over multiple time steps.
+ */
+ float alpha = 0.0f;
+
+ /* Number of substeps to perform.
+ * More substeps can be faster overall because of reduced search radius for collisions. */
+ int substep_count = 20;
+
+ /* Maximum overall distance a particle can move during a step.
+ * Divide by substep count to get max substep travel.
+ * This determines a the search radius for collisions.
+ * A larger travel distance means the point can move faster,
+ * but it can take longer to find collisions. */
+ float max_travel_distance = 0.1f;
+
+ /* Maximum number of simultaneous contacts to record per point. */
+ int max_contacts_per_point = 4;
+
+ /* Branching factor for the surface mesh BVH. */
+ int bvh_branching_factor = 2;
+
+ /* Number of iterations to satisfy constraints. */
+ int max_solver_iterations = 5;
+
+ /* Acceptable error threshold for convergence, in length units. */
+ float error_threshold = 1.0e-4f;
+ };
+
+ struct Result {
+ enum Status {
+ Ok,
+ ErrorNoConvergence,
+ };
+
+ Status status = Status::Ok;
+
+ /* True if any point's original travel was larger than the allowed maximum.
+ * If clamping is enabled the point's travel will be shorter than the input. */
+ bool max_travel_exceeded = false;
+
+ /* Total number of constraints solved. */
+ int constraint_count = 0;
+
+ /* Residual error values to judge convergence.
+ * Eror computation must be explicitly enabled during solving. */
+ struct {
+ /* Root-mean-square of the constraint residuals, indicating numerical quality
+ * of the solution. For a positional solver this value is in length units
+ * and describes how far constraints are violated on average. */
+ double rms_error = 0.0;
+ /* Sum of squared errors (in length units). */
+ double error_squared_sum = 0.0;
+ /* Largest squared error. */
+ double max_error_squared = 0.0;
+ } residual;
+
+ struct {
+ /* Time in seconds for the entire step. */
+ double step_total = 0.0;
+ /* Time in seconds to build the BVH tree of the surface.
+ * This is zero if the surface BVH was cached. */
+ double build_bvh = 0.0;
+ /* Time in seconds to find contact points, cumulative over substeps. */
+ double find_contacts = 0.0;
+ /* Time in seconds to solve constraints, cumulative over substeps. */
+ double solve_constraints = 0.0;
+ } timing;
+ };
+
+ private:
+ Params params_;
+
+ /** Length of each segment indexed by the index of the first point in the segment. */
+ Array<float> segment_lengths_cu_;
+
+ struct Contact {
+ float dist_sq_;
+ float3 normal_;
+ float3 point_;
+ };
+
+ Array<int> contacts_num_;
+ Array<Contact> contacts_;
+
+ /** Information about the most recent step solution. */
+ mutable Result result_;
+
+ public:
+ const Params &params() const;
+
+ Span<float> segment_lengths() const;
+
+ const Result &result() const;
+ void clear_result();
+
+ /* Initialize the solver for a given set of curves.
+ * The solver must be reinitialized if the curve set changes. */
+ void initialize(const Params &params, const bke::CurvesGeometry &curves, IndexMask curve_selection);
+
+ /* Solve constraints for an independent subset of curves. */
+ void step_curves(bke::CurvesGeometry &curves,
+ const Mesh *surface,
+ const bke::CurvesSurfaceTransforms &transforms,
+ Span<float3> start_positions,
+ IndexMask changed_curves,
+ bool update_error = false);
+
+ private:
+ void find_contact_points(const bke::CurvesGeometry &curves,
+ const Mesh *surface,
+ const bke::CurvesSurfaceTransforms &transforms,
+ float max_dist,
+ IndexMask changed_curves);
+
+ void apply_distance_constraint(float3 &point_a,
+ float3 &point_b,
+ float segment_length,
+ float weight_a,
+ float weight_b) const;
+
+ float get_distance_constraint_error(const float3 &point_a,
+ const float3 &point_b,
+ const float segment_length) const;
+
+ void apply_contact_constraint(float3 &point,
+ float radius,
+ const Contact &contact) const;
+
+ float get_contact_constraint_error(const float3 &point,
+ float radius,
+ const Contact &contact) const;
+
+ void solve_constraints(bke::CurvesGeometry &curves, IndexMask changed_curves) const;
+
+ void solve_curve_constraints(bke::CurvesGeometry &curves,
+ const VArray<float> radius,
+ const IndexRange points) const;
+
+ void compute_error(const bke::CurvesGeometry &curves, IndexMask changed_curves) const;
+
+ void compute_curve_error(const bke::CurvesGeometry &curves,
+ const VArray<float> radius,
+ const IndexRange points) const;
+};
+
+} // namespace blender::geometry
diff --git a/source/blender/geometry/intern/constraint_solver.cc b/source/blender/geometry/intern/constraint_solver.cc
new file mode 100644
index 00000000000..a7d3dee0fb0
--- /dev/null
+++ b/source/blender/geometry/intern/constraint_solver.cc
@@ -0,0 +1,456 @@
+/* SPDX-License-Identifier: GPL-2.0-or-later */
+
+/** \file
+ * \ingroup bke
+ */
+
+#include "GEO_constraint_solver.hh"
+
+#include "BLI_index_mask_ops.hh"
+
+#include "BKE_bvhutils.h"
+#include "BKE_mesh_runtime.h"
+
+#include "DNA_mesh_types.h"
+#include "DNA_meshdata_types.h"
+#include "DNA_object_types.h"
+
+#include "PIL_time.h"
+
+namespace blender::geometry {
+
+using bke::CurvesGeometry;
+using bke::CurvesSurfaceTransforms;
+using threading::EnumerableThreadSpecific;
+
+static const int curves_grain_size = 64;
+
+const ConstraintSolver::Params &ConstraintSolver::params() const
+{
+ return params_;
+}
+
+Span<float> ConstraintSolver::segment_lengths() const
+{
+ return segment_lengths_cu_;
+}
+
+const ConstraintSolver::Result &ConstraintSolver::result() const
+{
+ return result_;
+}
+
+void ConstraintSolver::clear_result()
+{
+ result_ = Result{};
+}
+
+void ConstraintSolver::initialize(const Params &params,
+ const CurvesGeometry &curves,
+ IndexMask curve_selection)
+{
+ params_ = params;
+
+ if (params_.use_length_constraints) {
+ segment_lengths_cu_.reinitialize(curves.points_num());
+
+ const Span<float3> positions_cu = curves.positions();
+ threading::parallel_for(curve_selection.index_range(), 256, [&](const IndexRange range) {
+ for (const int curve_i : curve_selection.slice(range)) {
+ const IndexRange points = curves.points_for_curve(curve_i).drop_back(1);
+
+ float length_cu = 0.0f, prev_length_cu;
+ for (const int point_i : points) {
+ const float3 &p1_cu = positions_cu[point_i];
+ const float3 &p2_cu = positions_cu[point_i + 1];
+ prev_length_cu = length_cu;
+ length_cu = math::distance(p1_cu, p2_cu);
+ segment_lengths_cu_[point_i] = length_cu;
+ }
+ }
+ });
+ }
+ else {
+ segment_lengths_cu_.reinitialize(0);
+ }
+
+ if (params_.use_collision_constraints) {
+ contacts_num_.reinitialize(curves.points_num());
+ contacts_.reinitialize(params_.max_contacts_per_point * curves.points_num());
+ }
+ else {
+ contacts_num_.reinitialize(0);
+ contacts_.reinitialize(0);
+ }
+}
+
+void ConstraintSolver::step_curves(CurvesGeometry &curves,
+ const Mesh *surface,
+ const CurvesSurfaceTransforms &transforms,
+ const Span<float3> start_positions,
+ const IndexMask changed_curves,
+ bool update_error)
+{
+ const double step_start = PIL_check_seconds_timer();
+
+ clear_result();
+
+ const MutableSpan<float3> positions = curves.positions_for_write();
+
+ const float max_substep_travel_distance = params_.max_travel_distance / params_.substep_count;
+ const float max_collision_distance = 2.0f * max_substep_travel_distance;
+ const float max_travel_distance_sq = params_.max_travel_distance * params_.max_travel_distance;
+
+ const bool clamp_travel = true;
+
+ /* Compute position delta per substep ("velocity") */
+ Array<float3> delta_substep(curves.points_num());
+ threading::parallel_for(
+ changed_curves.index_range(), curves_grain_size, [&](const IndexRange range) {
+ for (const int curve_i : changed_curves.slice(range)) {
+ const IndexRange points = curves.points_for_curve(curve_i);
+ for (const int point_i : points) {
+ const float3 delta_step = positions[point_i] - start_positions[point_i];
+ positions[point_i] = start_positions[point_i];
+
+ const float travel_sq = len_squared_v3(delta_step);
+ if (travel_sq <= max_travel_distance_sq) {
+ delta_substep[point_i] = delta_step / params_.substep_count;
+ continue;
+ }
+
+ result_.max_travel_exceeded = true;
+ if (clamp_travel) {
+ delta_substep[point_i] = math::normalize(delta_step) * max_substep_travel_distance;
+ }
+ else {
+ delta_substep[point_i] = delta_step / params_.substep_count;
+ }
+ }
+ }
+ });
+
+ for (const int substep : IndexRange(params_.substep_count)) {
+ /* Set unconstrained position: x <- x + v*dt */
+ threading::parallel_for(
+ changed_curves.index_range(), curves_grain_size, [&](const IndexRange range) {
+ for (const int curve_i : changed_curves.slice(range)) {
+ const IndexRange points = curves.points_for_curve(curve_i);
+ for (const int point_i : points) {
+ positions[point_i] += delta_substep[point_i];
+ }
+ }
+ });
+
+ if (params_.use_collision_constraints) {
+ find_contact_points(curves, surface, transforms, max_collision_distance, changed_curves);
+ }
+
+ solve_constraints(curves, changed_curves);
+ }
+
+ if (update_error) {
+ compute_error(curves, changed_curves);
+ }
+
+ result_.timing.step_total += PIL_check_seconds_timer() - step_start;
+}
+
+void ConstraintSolver::find_contact_points(const CurvesGeometry &curves,
+ const Mesh *surface,
+ const CurvesSurfaceTransforms &transforms,
+ const float max_dist,
+ const IndexMask changed_curves)
+{
+ /* Should be set when initializing constraints */
+ BLI_assert(contacts_num_.size() == curves.points_num());
+ BLI_assert(contacts_.size() == curves.points_num() * params_.max_contacts_per_point);
+
+ contacts_num_.fill(0);
+
+ if (surface == nullptr) {
+ return;
+ }
+
+ const float curves_to_surface_scale = mat4_to_scale(transforms.curves_to_surface.ptr());
+ const float surface_to_curves_scale = mat4_to_scale(transforms.curves_to_surface.ptr());
+ const float max_dist_su = curves_to_surface_scale * max_dist;
+ const float max_dist_sq_su = max_dist_su * max_dist_su;
+
+ const Span<MLoopTri> surface_looptris = {BKE_mesh_runtime_looptri_ensure(surface),
+ BKE_mesh_runtime_looptri_len(surface)};
+
+ const double build_bvh_start = PIL_check_seconds_timer();
+
+ /** BVH tree of the surface mesh for finding collisions. */
+ BVHTreeFromMesh surface_bvh;
+ BKE_bvhtree_from_mesh_get(
+ &surface_bvh, surface, BVHTREE_FROM_LOOPTRI, params_.bvh_branching_factor);
+ BLI_SCOPED_DEFER([&]() { free_bvhtree_from_mesh(&surface_bvh); });
+ if (!surface_bvh.cached) {
+ result_.timing.build_bvh += PIL_check_seconds_timer() - build_bvh_start;
+ }
+
+ double find_contacts_start = PIL_check_seconds_timer();
+ threading::parallel_for(
+ changed_curves.index_range(), curves_grain_size, [&](const IndexRange range) {
+ for (const int curve_i : changed_curves.slice(range)) {
+ /* First point is anchored to the surface, ignore collisions. */
+ const IndexRange points = params_.use_root_constraints ?
+ curves.points_for_curve(curve_i).drop_front(1) :
+ curves.points_for_curve(curve_i);
+ for (const int point_i : points) {
+ const float3 &new_p = curves.positions()[point_i];
+
+ const MutableSpan<Contact> contacts = contacts_.as_mutable_span().slice(
+ params_.max_contacts_per_point * point_i, params_.max_contacts_per_point);
+
+ const float3 p_su = transforms.curves_to_surface * new_p;
+ BLI_bvhtree_range_query_cpp(
+ *surface_bvh.tree,
+ p_su,
+ max_dist_su,
+ [&](const int triangle_i, const float3 &co_su, float dist_sq_su) {
+ const MLoopTri &looptri = surface_looptris[triangle_i];
+ const float3 v0_su = surface->mvert[surface->mloop[looptri.tri[0]].v].co;
+ const float3 v1_su = surface->mvert[surface->mloop[looptri.tri[1]].v].co;
+ const float3 v2_su = surface->mvert[surface->mloop[looptri.tri[2]].v].co;
+ float3 closest_su;
+ closest_on_tri_to_point_v3(closest_su, co_su, v0_su, v1_su, v2_su);
+ dist_sq_su = len_squared_v3v3(co_su, closest_su);
+ if (dist_sq_su <= max_dist_sq_su) {
+ const int contacts_num = contacts_num_[point_i];
+ int insert_i;
+ if (contacts_num < params_.max_contacts_per_point) {
+ insert_i = contacts_num;
+ ++contacts_num_[point_i];
+ }
+ else {
+ /* Replace the contact with the largest distance. */
+ insert_i = -1;
+ float max_dist_sq_su = dist_sq_su;
+ for (int contact_i : IndexRange(4)) {
+ if (contacts[contact_i].dist_sq_ > max_dist_sq_su) {
+ insert_i = contact_i;
+ max_dist_sq_su = contacts[contact_i].dist_sq_;
+ }
+ }
+ }
+ if (insert_i >= 0) {
+ float3 normal_su;
+ normal_tri_v3(normal_su, v0_su, v1_su, v2_su);
+ contacts[insert_i] = Contact{
+ max_dist_sq_su,
+ transforms.surface_to_curves_normal * float3{normal_su},
+ transforms.surface_to_curves * float3{closest_su}};
+ }
+ }
+ });
+ }
+ }
+ });
+ result_.timing.find_contacts += PIL_check_seconds_timer() - find_contacts_start;
+}
+
+void ConstraintSolver::apply_distance_constraint(float3 &point_a,
+ float3 &point_b,
+ const float segment_length,
+ const float weight_a,
+ const float weight_b) const
+{
+ float length_cu;
+ const float3 direction = math::normalize_and_get_length(point_b - point_a, length_cu);
+ /* Constraint function */
+ const float C = length_cu - segment_length;
+ const float3 gradient = direction;
+
+ /* Lagrange multiplier */
+ const float lambda = -C / (weight_a + weight_b + params_.alpha);
+ point_a -= gradient * lambda * weight_a;
+ point_b += gradient * lambda * weight_b;
+}
+
+float ConstraintSolver::get_distance_constraint_error(const float3 &point_a,
+ const float3 &point_b,
+ const float segment_length) const
+{
+ float length_cu = math::length(point_b - point_a);
+ /* Constraint function */
+ const float C = length_cu - segment_length;
+ return C;
+}
+
+void ConstraintSolver::apply_contact_constraint(float3 &point,
+ const float radius,
+ const ConstraintSolver::Contact &contact) const
+{
+ /* Constraint function */
+ const float C = math::dot(point - contact.point_, contact.normal_) - radius;
+ const float3 gradient = contact.normal_;
+
+ /* Lagrange multiplier */
+ const float lambda = -C / (1.0f + params_.alpha);
+ if (lambda > 0.0f) {
+ point += gradient * lambda;
+ }
+}
+
+float ConstraintSolver::get_contact_constraint_error(
+ const float3 &point, const float radius, const ConstraintSolver::Contact &contact) const
+{
+ /* Constraint function */
+ const float C = math::dot(point - contact.point_, contact.normal_) - radius;
+ return math::min(C, 0.0f);
+}
+
+void ConstraintSolver::solve_constraints(CurvesGeometry &curves, const IndexMask changed_curves) const
+{
+ const int solver_max_iterations = [&]() {
+ switch (params_.solver_type) {
+ case SolverType::Sequential:
+ return 1;
+ case SolverType::PositionBasedDynamics:
+ return params_.max_solver_iterations;
+ }
+ return 0;
+ }();
+
+ const double solve_constraints_start = PIL_check_seconds_timer();
+
+ VArray<float> radius = curves.attributes().lookup_or_default<float>(
+ "radius", ATTR_DOMAIN_POINT, 0.0f);
+
+ threading::parallel_for(
+ changed_curves.index_range(), curves_grain_size, [&](const IndexRange range) {
+ for (const int curve_i : changed_curves.slice(range)) {
+ const IndexRange points = curves.points_for_curve(curve_i);
+
+ /* Solve constraints */
+ for (const int solver_i : IndexRange(solver_max_iterations)) {
+ solve_curve_constraints(curves, radius, points);
+ }
+ }
+ });
+
+ result_.timing.solve_constraints += PIL_check_seconds_timer() - solve_constraints_start;
+}
+
+void ConstraintSolver::solve_curve_constraints(CurvesGeometry &curves,
+ const VArray<float> radius,
+ const IndexRange points) const
+{
+ const int skipped_root_points = [&]() {
+ switch (params_.solver_type) {
+ /* The sequential solver only moves the 2nd point of each segment. */
+ case SolverType::Sequential:
+ return (int)points.size();
+ /* The PBD solver moves both points, except for the pinned root. */
+ case SolverType::PositionBasedDynamics:
+ return params_.use_root_constraints ? 1 : 0;
+ }
+ return 0;
+ }();
+
+ MutableSpan<float3> positions_cu = curves.positions_for_write();
+
+ result_.constraint_count = 0;
+
+ /* Distance constraints */
+ if (params_.use_length_constraints) {
+ result_.constraint_count += points.size() - 1;
+ for (const int segment_i : IndexRange(points.size() - 1)) {
+ const int point_a = points[segment_i];
+ const int point_b = points[segment_i + 1];
+ const float segment_length = segment_lengths_cu_[point_a];
+ float3 &pa = positions_cu[point_a];
+ float3 &pb = positions_cu[point_b];
+
+ const float w0 = (segment_i < skipped_root_points ? 0.0f : 1.0f);
+ const float w1 = 1.0f;
+ apply_distance_constraint(pa, pb, segment_length, w0, w1);
+ }
+ }
+
+ /* Contact constraints */
+ if (params_.use_collision_constraints) {
+ for (const int point_i : points.drop_front(skipped_root_points)) {
+ float3 &p = positions_cu[point_i];
+ const float radius_p = radius[point_i];
+ const int contacts_num = contacts_num_[point_i];
+ result_.constraint_count += contacts_num;
+
+ const Span<Contact> contacts = contacts_.as_span().slice(
+ params_.max_contacts_per_point * point_i, contacts_num);
+ for (const Contact &c : contacts) {
+ apply_contact_constraint(p, radius_p, c);
+ }
+ }
+ }
+}
+
+void ConstraintSolver::compute_error(const CurvesGeometry &curves, const IndexMask changed_curves) const
+{
+ VArray<float> radius = curves.attributes().lookup_or_default<float>(
+ "radius", ATTR_DOMAIN_POINT, 0.0f);
+
+ /* Accumulate error (no threading) */
+ for (const int curve_i : changed_curves) {
+ const IndexRange points = curves.points_for_curve(curve_i);
+ compute_curve_error(curves, radius, points);
+ }
+
+ if (result_.constraint_count > 0) {
+ result_.residual.rms_error = sqrt(result_.residual.error_squared_sum /
+ result_.constraint_count);
+ }
+ else {
+ result_.residual.rms_error = 0.0;
+ }
+
+ if (result_.residual.max_error_squared > params_.error_threshold * params_.error_threshold) {
+ result_.status = Result::Status::ErrorNoConvergence;
+ }
+}
+
+void ConstraintSolver::compute_curve_error(const CurvesGeometry &curves,
+ const VArray<float> radius,
+ const IndexRange points) const
+{
+ Span<float3> positions_cu = curves.positions();
+
+ /* Distance constraints */
+ if (params_.use_length_constraints) {
+ for (const int segment_i : IndexRange(points.size() - 1)) {
+ const int point_a = points[segment_i];
+ const int point_b = points[segment_i + 1];
+ const float segment_length = segment_lengths_cu_[point_a];
+ const float3 &pa = positions_cu[point_a];
+ const float3 &pb = positions_cu[point_b];
+
+ const float error = get_distance_constraint_error(pa, pb, segment_length);
+ const double error_sq = error * error;
+ result_.residual.error_squared_sum += error_sq;
+ result_.residual.max_error_squared = std::max(result_.residual.max_error_squared, error_sq);
+ }
+ }
+
+ /* Contact constraints */
+ if (params_.use_collision_constraints) {
+ for (const int point_i : points) {
+ const float3 &p = positions_cu[point_i];
+ const float radius_p = radius[point_i];
+ const int contacts_num = contacts_num_[point_i];
+ const Span<Contact> contacts = contacts_.as_span().slice(
+ params_.max_contacts_per_point * point_i, contacts_num);
+ for (const Contact &c : contacts) {
+ const float error = get_contact_constraint_error(p, radius_p, c);
+ const double error_sq = error * error;
+ result_.residual.error_squared_sum += error_sq;
+ result_.residual.max_error_squared = std::max(result_.residual.max_error_squared,
+ error_sq);
+ }
+ }
+ }
+}
+
+} // namespace blender::geometry
diff --git a/source/blender/geometry/tests/GEO_constraint_solver_test.cc b/source/blender/geometry/tests/GEO_constraint_solver_test.cc
new file mode 100644
index 00000000000..efb29e86755
--- /dev/null
+++ b/source/blender/geometry/tests/GEO_constraint_solver_test.cc
@@ -0,0 +1,85 @@
+/* SPDX-License-Identifier: GPL-2.0-or-later */
+
+/** \file
+ * \ingroup bke
+ */
+
+#include "testing/testing.h"
+
+#include "BKE_curves.hh"
+
+#include "GEO_constraint_solver.hh"
+
+namespace blender::geometry::tests {
+
+using bke::CurvesGeometry;
+using bke::CurvesSurfaceTransforms;
+
+inline CurvesSurfaceTransforms create_curves_surface_transforms()
+{
+ CurvesSurfaceTransforms transforms;
+ transforms.curves_to_world = float4x4::identity();
+ transforms.curves_to_surface = float4x4::identity();
+ transforms.world_to_curves = float4x4::identity();
+ transforms.world_to_surface = float4x4::identity();
+ transforms.surface_to_world = float4x4::identity();
+ transforms.surface_to_curves = float4x4::identity();
+ transforms.surface_to_curves_normal = float4x4::identity();
+ return transforms;
+}
+
+TEST(curves_constraints, LengthAndRootConstraint)
+{
+ CurvesGeometry curves(9, 3);
+ curves.fill_curve_types(CURVE_TYPE_POLY);
+ const MutableSpan<int> point_offsets = curves.offsets_for_write();
+ point_offsets[0] = 0;
+ point_offsets[1] = 2;
+ point_offsets[2] = 6;
+ point_offsets[3] = 9;
+ const MutableSpan<float3> positions = curves.positions_for_write();
+ positions[0] = float3(.0f, 0, 0);
+ positions[1] = float3(.1f, 0, 0);
+
+ positions[2] = float3(.0f, 0, 1);
+ positions[3] = float3(.1f, 0, 1);
+ positions[4] = float3(.15f, 0, 1);
+
+ positions[5] = float3(.0f, 0, 2);
+ positions[6] = float3(.1f, 0, 2);
+ positions[7] = float3(.15f, 0, 2);
+ positions[8] = float3(.25f, 0, 2);
+
+ const CurvesSurfaceTransforms transforms = create_curves_surface_transforms();
+
+ ConstraintSolver solver;
+ ConstraintSolver::Params params;
+ params.use_collision_constraints = false;
+
+ solver.initialize(params, curves, curves.curves_range());
+
+ const Array<float3> orig_positions = curves.positions();
+
+ positions[1].y += 0.1f;
+ positions[3].y += 0.1f;
+ positions[6].y += 0.1f;
+
+ solver.step_curves(curves, nullptr, transforms, orig_positions, curves.curves_range());
+
+ EXPECT_EQ(solver.result().status, ConstraintSolver::Result::Status::Ok);
+ EXPECT_LE(solver.result().residual.max_error_squared, params.error_threshold * params.error_threshold);
+ EXPECT_LE(solver.result().residual.rms_error, params.error_threshold);
+
+ const float eps = 0.005f;
+ EXPECT_V3_NEAR(positions[0], float3(0.0f, 0.0f, 0.0f), eps);
+ EXPECT_V3_NEAR(positions[1], float3(0.065f, 0.075f, 0.0f), eps);
+ EXPECT_V3_NEAR(positions[2], float3(0.0f, 0.0f, 1.0f), eps);
+ EXPECT_V3_NEAR(positions[3], float3(0.0824425220, 0.057f, 1.0f), eps);
+ EXPECT_V3_NEAR(positions[4], float3(0.118486673, 0.022f, 1.0f), eps);
+ EXPECT_V3_NEAR(positions[5], float3(0.0f, 0.0f, 2.0f), eps);
+ EXPECT_V3_NEAR(positions[6], float3(0.1f, 0.1f, 2.0f), eps);
+ EXPECT_V3_NEAR(positions[7], float3(0.125f, 0.057f, 2.0f), eps);
+ EXPECT_V3_NEAR(positions[8], float3(0.213f, 0.009f, 2.0f), eps);
+}
+
+} // namespace blender::geometry::tests
diff --git a/source/blender/geometry/tests/performance/CMakeLists.txt b/source/blender/geometry/tests/performance/CMakeLists.txt
new file mode 100644
index 00000000000..228b3a17f60
--- /dev/null
+++ b/source/blender/geometry/tests/performance/CMakeLists.txt
@@ -0,0 +1,11 @@
+# SPDX-License-Identifier: GPL-2.0-or-later
+# Copyright 2014 Blender Foundation. All rights reserved.
+
+set(INC
+ .
+ ..
+)
+
+include_directories(${INC})
+
+BLENDER_TEST_PERFORMANCE(GEO_constraint_solver_performance "bf_geometry")
diff --git a/source/blender/geometry/tests/performance/GEO_constraint_solver_performance_test.cc b/source/blender/geometry/tests/performance/GEO_constraint_solver_performance_test.cc
new file mode 100644
index 00000000000..b5b39fd799e
--- /dev/null
+++ b/source/blender/geometry/tests/performance/GEO_constraint_solver_performance_test.cc
@@ -0,0 +1,359 @@
+/* SPDX-License-Identifier: GPL-2.0-or-later */
+
+/** \file
+ * \ingroup bke
+ */
+
+#include "testing/testing.h"
+
+#include "BLI_noise.hh"
+#include "BLI_rand.hh"
+
+#include "BKE_curves.hh"
+#include "BKE_idtype.h"
+#include "BKE_lib_id.h"
+#include "BKE_mesh.h"
+
+#include "DNA_mesh_types.h"
+#include "DNA_meshdata_types.h"
+
+#include "GEO_constraint_solver.hh"
+
+namespace blender::geometry::tests {
+
+using bke::CurvesGeometry;
+using bke::CurvesSurfaceTransforms;
+
+class CurveConstraintSolverPerfTestSuite : public testing::Test {
+ public:
+ /* Sets up Blender just enough to not crash on creating a mesh. */
+ static void SetUpTestSuite()
+ {
+ testing::Test::SetUpTestSuite();
+
+ //CLG_init();
+ BLI_threadapi_init();
+
+ //DNA_sdna_current_init();
+ //BKE_blender_globals_init();
+
+ BKE_idtype_init();
+ }
+
+ static void TearDownTestSuite()
+ {
+ BLI_threadapi_exit();
+
+ //BKE_blender_atexit();
+
+ //BKE_tempdir_session_purge();
+ //BKE_appdir_exit();
+ //CLG_exit();
+
+ testing::Test::TearDownTestSuite();
+ }
+};
+
+inline CurvesSurfaceTransforms create_curves_surface_transforms()
+{
+ CurvesSurfaceTransforms transforms;
+ transforms.curves_to_world = float4x4::identity();
+ transforms.curves_to_surface = float4x4::identity();
+ transforms.world_to_curves = float4x4::identity();
+ transforms.world_to_surface = float4x4::identity();
+ transforms.surface_to_world = float4x4::identity();
+ transforms.surface_to_curves = float4x4::identity();
+ transforms.surface_to_curves_normal = float4x4::identity();
+ return transforms;
+}
+
+const uint32_t randomized_curves_seed = 12345;
+const uint32_t randomized_offset_seed = 23451;
+
+static float3 random_point_inside_unit_sphere(RandomNumberGenerator &rng)
+{
+ const float theta = (float)(M_PI * 2.0) * rng.get_float();
+ const float phi = acosf(2.0f * rng.get_float() - 1.0f);
+ const float r = sqrt3f(rng.get_float());
+ return r * float3{sinf(phi) * cosf(theta), sinf(phi) * sinf(theta), cosf(phi)};
+}
+
+static Mesh *create_noise_grid(const float noise = 0.1f, const int resolution = 100, const float size = 1.0f)
+{
+ const int tot_verts = resolution * resolution;
+ const int tot_polys = (resolution - 1) * (resolution - 1);
+ const int tot_loops = tot_polys * 4;
+ Mesh *mesh = BKE_mesh_new_nomain(tot_verts, 0, 0, tot_loops, tot_polys);
+ const MutableSpan<MVert> mverts(mesh->mvert, mesh->totvert);
+ const MutableSpan<MPoly> mpolys(mesh->mpoly, mesh->totpoly);
+ const MutableSpan<MLoop> mloops(mesh->mloop, mesh->totloop);
+
+ for (const int i : IndexRange(resolution)) {
+ for (const int j : IndexRange(resolution)) {
+ float3 co = float3((float)i - 0.5f, (float)j - 0.5f, 0) * size;
+ const float3 offset = noise::perlin_float3_fractal_distorted(co, 2.0f, 0.5f, 0.0f);
+ co += noise * (offset - float3(0.5f));
+
+ const int vert_i = i * resolution + j;
+ copy_v3_v3(mverts[vert_i].co, co);
+ }
+ }
+
+ for (const int i : IndexRange(resolution - 1)) {
+ for (const int j : IndexRange(resolution - 1)) {
+ const int vert_i = i * resolution + j;
+ const int poly_i = i * (resolution - 1) + j;
+ const int loop_i = poly_i * 4;
+
+ mpolys[poly_i].loopstart = loop_i;
+ mpolys[poly_i].totloop = 4;
+
+ mloops[loop_i + 0].v = vert_i;
+ mloops[loop_i + 1].v = vert_i + 1;
+ mloops[loop_i + 2].v = vert_i + resolution + 1;
+ mloops[loop_i + 3].v = vert_i + resolution;
+ }
+ }
+
+ BKE_mesh_calc_edges(mesh, false, false);
+
+ return mesh;
+}
+
+static Mesh *create_torus(const int major_segments = 64,
+ const int minor_segments = 16,
+ const float major_radius = 1.0f,
+ const float minor_radius = 0.5f)
+{
+ const int tot_verts = major_segments * minor_segments;
+ const int tot_polys = major_segments * minor_segments;
+ const int tot_loops = tot_polys * 4;
+ Mesh *mesh = BKE_mesh_new_nomain(tot_verts, 0, 0, tot_loops, tot_polys);
+ const MutableSpan<MVert> mverts(mesh->mvert, mesh->totvert);
+ const MutableSpan<MPoly> mpolys(mesh->mpoly, mesh->totpoly);
+ const MutableSpan<MLoop> mloops(mesh->mloop, mesh->totloop);
+
+ for (const int i : IndexRange(major_segments)) {
+ for (const int j : IndexRange(minor_segments)) {
+ const float alpha = 2.0 * M_PI * i / major_segments;
+ const float beta = 2.0 * M_PI * j / minor_segments;
+ const float3 tmp = float3(cosf(beta) + major_radius, 0.0f, sinf(beta)) * minor_radius;
+ const float3 co = float3(tmp.x * cosf(alpha), tmp.x * sinf(alpha), tmp.z);
+
+ const int vert_i = i * minor_segments + j;
+ copy_v3_v3(mverts[vert_i].co, co);
+ }
+ }
+
+ for (const int i : IndexRange(major_segments)) {
+ for (const int j : IndexRange(minor_segments)) {
+ const int vert_i = i * minor_segments + j;
+ const int poly_i = i * minor_segments + j;
+ const int loop_i = poly_i * 4;
+
+ mpolys[poly_i].loopstart = loop_i;
+ mpolys[poly_i].totloop = 4;
+
+ const int di = i < major_segments - 1 ? minor_segments : minor_segments - tot_verts;
+ const int dj = j < minor_segments - 1 ? 1 : 1 - minor_segments;
+ mloops[loop_i + 0].v = vert_i;
+ mloops[loop_i + 1].v = vert_i + dj;
+ mloops[loop_i + 2].v = vert_i + di + dj;
+ mloops[loop_i + 3].v = vert_i + di;
+ }
+ }
+
+ BKE_mesh_calc_edges(mesh, false, false);
+
+ return mesh;
+}
+
+static CurvesGeometry create_randomized_curves(const int curve_num,
+ const int point_num_min,
+ const int point_num_max,
+ const float dist_min,
+ const float dist_max)
+{
+ RandomNumberGenerator rng(randomized_curves_seed);
+
+ Array<int> point_offsets(curve_num + 1);
+ const int point_num_range = std::max(point_num_max - point_num_min, 0);
+ int point_num = 0;
+ for (int curve_i : IndexRange(curve_num)) {
+ point_offsets[curve_i] = point_num;
+ point_num += point_num_min + (rng.get_int32() % point_num_range);
+ }
+ point_offsets.last() = point_num;
+
+ CurvesGeometry curves(point_num, curve_num);
+ curves.fill_curve_types(CURVE_TYPE_POLY);
+ curves.offsets_for_write().copy_from(point_offsets);
+
+ const MutableSpan<float3> positions = curves.positions_for_write();
+ for (int curve_i : curves.curves_range()) {
+ float3 pos = random_point_inside_unit_sphere(rng);
+ for (int point_i : curves.points_for_curve(curve_i)) {
+ positions[point_i] = pos;
+ pos += rng.get_unit_float3() * interpf(dist_max, dist_min, rng.get_float());
+ }
+ }
+
+ return curves;
+}
+
+static void randomized_point_offset(CurvesGeometry &curves,
+ IndexMask changed_curves,
+ float dist_min,
+ float dist_max,
+ float3 direction = float3(1, 0, 0),
+ float cone_angle = M_PI)
+{
+ RandomNumberGenerator rng(randomized_offset_seed);
+
+ math::normalize(direction);
+ float3 n1, n2;
+ ortho_basis_v3v3_v3(n1, n2, direction);
+
+ const MutableSpan<float3> positions = curves.positions_for_write();
+ for (const int curve_i : changed_curves) {
+ for (int point_i : curves.points_for_curve(curve_i)) {
+ const float theta = rng.get_float() * cone_angle;
+ const float phi = rng.get_float() * (float)(2.0 * M_PI);
+ const float3 dir_p = direction * cosf(theta) + n1 * sinf(theta) * cosf(phi) +
+ n2 * sinf(theta) * sinf(phi);
+ const float dist_p = interpf(dist_max, dist_min, rng.get_float());
+ positions[point_i] += dir_p * dist_p;
+ }
+ }
+}
+
+static void print_test_stats(const CurvesGeometry &curves, const ConstraintSolver::Result &result)
+{
+ const testing::TestInfo *const test_info = testing::UnitTest::GetInstance()->current_test_info();
+
+ std::cout << "Curves: " << curves.curves_num() << " Points: " << curves.points_num() << std::endl;
+ std::cout << "RMS=" << result.residual.rms_error
+ << " max error=" << sqrt(result.residual.max_error_squared)
+ << std::endl;
+ std::cout << "total: " << result.timing.step_total * 1000.0f
+ << " ms, build bvh: " << result.timing.build_bvh * 1000.0f
+ << " ms, find contacts: " << result.timing.find_contacts * 1000.0f
+ << " ms, solve: " << result.timing.solve_constraints * 1000.0f << " ms" << std::endl;
+}
+
+template <typename ParamType>
+class SolverPerfTestSuite : public CurveConstraintSolverPerfTestSuite,
+ public testing::WithParamInterface<ParamType> {
+ public:
+ struct TestResult {
+ ParamType param;
+ ConstraintSolver::Result solver_result;
+ };
+
+ static Vector<TestResult> &results()
+ {
+ static Vector<TestResult> results_;
+ return results_;
+ }
+
+ static void SetUpTestSuite()
+ {
+ CurveConstraintSolverPerfTestSuite::SetUpTestSuite();
+
+ results().clear();
+ }
+
+ static void TearDownTestSuite()
+ {
+ /* CSV printout for simple data import */
+ std::cout << "Parameter,RMS Error,Max Error,Collision Detection (ms),Solve Time (ms)" << std::endl;
+ for (const TestResult &result : results()) {
+ std::cout << result.param << "," << result.solver_result.residual.rms_error << ","
+ << sqrtf(result.solver_result.residual.max_error_squared) << ","
+ << (result.solver_result.timing.find_contacts * 1000.0) << ","
+ << (result.solver_result.timing.solve_constraints * 1000.0) << std::endl;
+ }
+
+ CurveConstraintSolverPerfTestSuite::TearDownTestSuite();
+ }
+
+ void randomized_test(const ParamType &test_param,
+ const ConstraintSolver::Params &solver_params,
+ const int mesh_resolution = 100)
+ {
+ CurvesGeometry curves = create_randomized_curves(10000, 4, 50, 0.1f, 0.2f);
+ const CurvesSurfaceTransforms transforms = create_curves_surface_transforms();
+
+ Mesh *surface = create_torus(mesh_resolution * 2, mesh_resolution, 1.0f, 0.5f);
+
+ ConstraintSolver solver;
+ solver.initialize(solver_params, curves, curves.curves_range());
+
+ const Array<float3> orig_positions = curves.positions();
+ randomized_point_offset(curves, curves.curves_range(), 0.0f, 1.0f);
+ solver.step_curves(curves, surface, transforms, orig_positions, curves.curves_range(), true);
+
+ BKE_id_free(nullptr, surface);
+
+ results().append(TestResult{test_param, solver.result()});
+ }
+};
+
+using SolverIterationsTestSuite = SolverPerfTestSuite<int>;
+
+TEST_P(SolverIterationsTestSuite, RandomizedTest)
+{
+ ConstraintSolver::Params params;
+ params.solver_type = ConstraintSolver::SolverType::PositionBasedDynamics;
+ params.max_solver_iterations = GetParam();
+
+ randomized_test(GetParam(), params);
+}
+
+INSTANTIATE_TEST_SUITE_P(curves_constraints_performance,
+ SolverIterationsTestSuite,
+ testing::Values(1, 5, 10, 20, 50, 100),
+ [](const testing::TestParamInfo<int> info) {
+ std::stringstream ss;
+ ss << "SolverIterationsTest_" << info.param;
+ return ss.str();
+ });
+
+using BVHBranchingFactorTestSuite = SolverPerfTestSuite<int>;
+
+TEST_P(BVHBranchingFactorTestSuite, RandomizedTest)
+{
+ ConstraintSolver::Params params;
+ params.bvh_branching_factor = GetParam();
+
+ randomized_test(GetParam(), params);
+}
+
+INSTANTIATE_TEST_SUITE_P(curves_constraints_performance,
+ BVHBranchingFactorTestSuite,
+ testing::Values(2, 4, 6, 8, 16, 32),
+ [](const testing::TestParamInfo<int> info) {
+ std::stringstream ss;
+ ss << "BVHBranchingFactorTest_" << info.param;
+ return ss.str();
+ });
+
+using MeshDensityTestSuite = SolverPerfTestSuite<int>;
+
+TEST_P(MeshDensityTestSuite, RandomizedTest)
+{
+ ConstraintSolver::Params params;
+
+ randomized_test(GetParam(), params, GetParam());
+}
+
+INSTANTIATE_TEST_SUITE_P(curves_constraints_performance,
+ MeshDensityTestSuite,
+ testing::Values(50, 100, 150, 200, 250),
+ [](const testing::TestParamInfo<int> info) {
+ std::stringstream ss;
+ ss << "MeshDensityTest_" << info.param;
+ return ss.str();
+ });
+
+} // namespace blender::geometry::tests
diff --git a/source/blender/makesdna/DNA_curves_types.h b/source/blender/makesdna/DNA_curves_types.h
index 89deeec898b..9e7163f2515 100644
--- a/source/blender/makesdna/DNA_curves_types.h
+++ b/source/blender/makesdna/DNA_curves_types.h
@@ -155,6 +155,7 @@ typedef struct Curves {
enum {
HA_DS_EXPAND = (1 << 0),
CV_SCULPT_SELECTION_ENABLED = (1 << 1),
+ CV_SCULPT_COLLISION_ENABLED = (1 << 2),
};
/** #Curves.symmetry */
diff --git a/source/blender/makesrna/intern/rna_curves.c b/source/blender/makesrna/intern/rna_curves.c
index cb8b36f41d2..3e021b5775b 100644
--- a/source/blender/makesrna/intern/rna_curves.c
+++ b/source/blender/makesrna/intern/rna_curves.c
@@ -368,6 +368,13 @@ static void rna_def_curves(BlenderRNA *brna)
RNA_def_property_clear_flag(prop, PROP_ANIMATABLE);
RNA_def_property_update(prop, 0, "rna_Curves_update_draw");
+ prop = RNA_def_property(srna, "use_sculpt_collision", PROP_BOOLEAN, PROP_NONE);
+ RNA_def_property_boolean_sdna(prop, NULL, "flag", CV_SCULPT_COLLISION_ENABLED);
+ RNA_def_property_ui_text(
+ prop, "Use Sculpt Collision", "Enable collision handling with the surface during sculpting");
+ RNA_def_property_clear_flag(prop, PROP_ANIMATABLE);
+ RNA_def_property_update(prop, 0, "rna_Curves_update_draw");
+
/* attributes */
rna_def_attributes_common(srna);