Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 0 additions & 6 deletions cmake/recipes/pybind11.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,5 @@ if (NOT DEFINED Python_FIND_FRAMEWORK)
set(Python_FIND_FRAMEWORK "LAST")
endif ()

# Pybind11 still uses the deprecated FindPythonInterp. So let's call CMake's
# new FindPython module and set PYTHON_EXECUTABLE for Pybind11 to pick up.
# This works well with conda environments.
find_package(Python COMPONENTS Interpreter Development.Module REQUIRED)
set(PYTHON_EXECUTABLE ${Python_EXECUTABLE})

include(CPM)
CPMAddPackage("gh:pybind/pybind11@2.13.1")
17 changes: 0 additions & 17 deletions docs/source/Doxyfile
Original file line number Diff line number Diff line change
Expand Up @@ -1387,15 +1387,6 @@ HTML_COLORSTYLE_SAT = 100

HTML_COLORSTYLE_GAMMA = 80

# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML
# page will contain the date and time when the page was generated. Setting this
# to YES can help to show when doxygen was last run and thus if the
# documentation is up to date.
# The default value is: NO.
# This tag requires that the tag GENERATE_HTML is set to YES.

HTML_TIMESTAMP = NO

# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML
# documentation will contain a main index with vertical navigation menus that
# are dynamically created via JavaScript. If disabled, the navigation index will
Expand Down Expand Up @@ -2056,14 +2047,6 @@ LATEX_HIDE_INDICES = NO

LATEX_BIB_STYLE = plainnat

# If the LATEX_TIMESTAMP tag is set to YES then the footer of each generated
# page will contain the date and time when the page was generated. Setting this
# to NO can help when comparing the output of multiple runs.
# The default value is: NO.
# This tag requires that the tag GENERATE_LATEX is set to YES.

LATEX_TIMESTAMP = NO

# The LATEX_EMOJI_DIRECTORY tag is used to specify the (relative or absolute)
# path from which the emoji images will be read. If a relative path is entered,
# it will be relative to the LATEX_OUTPUT directory. If left blank the
Expand Down
15 changes: 15 additions & 0 deletions docs/source/tutorial/simulation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,21 @@ While the IPC Toolkit provides all the principle components of the IPC algorithm

We provide several helper functions to make your job easier. The following examples show how to use these functions.

Optimization-Based Time Integration
-----------------------------------

IPC defines barrier potential :math:`B(\mathbf{x})` and a friction potential :math:`D(\mathbf{v})`. To add these into a optimization-based time integration, we need to scale the potentials by the time-integrators acceleration scaling. For implicit Euler, this is h^2, where h is the timestep.

With elasticity :math:`\Psi(\mathbf{x})`, the total optimization problem is:

.. math::
\mathbf{x}^{t+1} = \underset{\mathbf{x}}{\arg\min} ~ \tfrac{1}{2} (\mathbf{x} - \hat{\mathbf{x}})^\top\mathbf{M}(\mathbf{x}-\hat{\mathbf{x}})+h^2\Psi(\mathbf{x}) + h^2 \kappa B(\mathbf{x}) + h^2 D(\mathbf{v}(\mathbf{x}))

where :math:`\hat{\mathbf{x}} = \mathbf{x}^t + h\mathbf{v}^t + h^2\mathbf{g}` is the time integration scheme-specific “predicted positions.”

.. note::
In \cite{Li2020}, all the constants are wrapped up into $\kappa$, which is adaptively modified. In follow-up works, we treat the barrier as a physical energy, and so it should have the same multiplier as the elastic energy ($h^2$ for implicit Euler).

Volumetric Meshes
-----------------

Expand Down
1 change: 0 additions & 1 deletion src/ipc/barrier/adaptive_stiffness.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ double update_barrier_stiffness(
/// @brief Compute the semi-implicit stiffness for a single collision.
/// See [Ando 2024] for details.
/// @param stencil Collision stencil.
/// @param vertex_ids Vertex indices of the collision.
/// @param vertices Vertex positions.
/// @param mass Vertex masses.
/// @param local_hess Local hessian of the elasticity energy function.
Expand Down
5 changes: 3 additions & 2 deletions src/ipc/candidates/candidates.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ class Candidates {
/// @param mesh The surface of the collision mesh.
/// @param vertices Surface vertex positions (rowwise).
/// @param inflation_radius Amount to inflate the bounding boxes.
/// @param broad_phase_method Broad phase method to use.
/// @param broad_phase Broad phase method to use.
void build(
const CollisionMesh& mesh,
Eigen::ConstRef<Eigen::MatrixXd> vertices,
Expand All @@ -34,7 +34,7 @@ class Candidates {
/// @param vertices_t0 Surface vertex starting positions (rowwise).
/// @param vertices_t1 Surface vertex ending positions (rowwise).
/// @param inflation_radius Amount to inflate the bounding boxes.
/// @param broad_phase_method Broad phase method to use.
/// @param broad_phase Broad phase method to use.
void build(
const CollisionMesh& mesh,
Eigen::ConstRef<Eigen::MatrixXd> vertices_t0,
Expand Down Expand Up @@ -99,6 +99,7 @@ class Candidates {
/// @param vertices_t1 Surface vertex ending positions (rowwise).
/// @param dhat Barrier activation distance.
/// @param min_distance The minimum distance allowable between any two elements.
/// @param broad_phase The broad phase algorithm to use.
/// @param narrow_phase_ccd The narrow phase CCD algorithm to use.
double compute_cfl_stepsize(
const CollisionMesh& mesh,
Expand Down
9 changes: 4 additions & 5 deletions src/ipc/ccd/additive_ccd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ class AdditiveCCD : public NarrowPhaseCCD {
static constexpr double DEFAULT_CONSERVATIVE_RESCALING = 0.9;

/// @brief Construct a new AdditiveCCD object.
/// @param max_iterations The maximum number of iterations to use for the CCD algorithm. If set to UNLIMITTED_ITERATIONS, the algorithm will run until it converges.
/// @param conservative_rescaling The conservative rescaling of the time of impact.
AdditiveCCD(
const long max_iterations = UNLIMITTED_ITERATIONS,
Expand All @@ -39,7 +40,6 @@ class AdditiveCCD : public NarrowPhaseCCD {
/// @param[out] toi The time of impact between the two points.
/// @param min_distance The minimum distance between two objects.
/// @param tmax The maximum time to check for collisions.
/// @param conservative_rescaling The conservative rescaling of the time of impact.
/// @return True if a collision was detected, false otherwise.
bool point_point_ccd(
Eigen::ConstRef<VectorMax3d> p0_t0,
Expand All @@ -60,7 +60,6 @@ class AdditiveCCD : public NarrowPhaseCCD {
/// @param[out] toi The time of impact between the point and the edge.
/// @param min_distance The minimum distance between two objects.
/// @param tmax The maximum time to check for collisions.
/// @param conservative_rescaling The conservative rescaling of the time of impact.
/// @return True if a collision was detected, false otherwise.
bool point_edge_ccd(
Eigen::ConstRef<VectorMax3d> p_t0,
Expand All @@ -85,7 +84,6 @@ class AdditiveCCD : public NarrowPhaseCCD {
/// @param[out] toi The time of impact between the point and the triangle.
/// @param min_distance The minimum distance between two objects.
/// @param tmax The maximum time to check for collisions.
/// @param conservative_rescaling The conservative rescaling of the time of impact.
/// @return True if a collision was detected, false otherwise.
bool point_triangle_ccd(
Eigen::ConstRef<Eigen::Vector3d> p_t0,
Expand All @@ -112,7 +110,6 @@ class AdditiveCCD : public NarrowPhaseCCD {
/// @param[out] toi The time of impact between the two edges.
/// @param min_distance The minimum distance between two objects.
/// @param tmax The maximum time to check for collisions.
/// @param conservative_rescaling The conservative rescaling of the time of impact.
/// @return True if a collision was detected, false otherwise.
bool edge_edge_ccd(
Eigen::ConstRef<Eigen::Vector3d> ea0_t0,
Expand All @@ -135,11 +132,13 @@ class AdditiveCCD : public NarrowPhaseCCD {

private:
/// @brief Computes the time of impact between two objects using additive continuous collision detection.
/// @param x Initial positions
/// @param dx Displacements
/// @param distance_squared A function that computes the squared distance between the two objects at a given time.
/// @param max_disp_mag The maximum displacement magnitude.
/// @param[out] toi The time of impact between the two objects.
/// @param min_distance The minimum distance between the objects.
/// @param tmax The maximum time to check for collisions.
/// @param conservative_rescaling The amount to rescale the objects by to ensure conservative advancement.
/// @return True if a collision was detected, false otherwise.
bool additive_ccd(
VectorMax12d x, // mutable copy
Expand Down
2 changes: 2 additions & 0 deletions src/ipc/ccd/tight_inclusion_ccd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ class TightInclusionCCD : public NarrowPhaseCCD {
static constexpr double SMALL_TOI = 1e-6;

/// @brief Construct a new AdditiveCCD object.
/// @param tolerance The tolerance used for the CCD algorithm.
/// @param max_iterations The maximum number of iterations for the CCD algorithm.
/// @param conservative_rescaling The conservative rescaling of the time of impact.
TightInclusionCCD(
const double tolerance = DEFAULT_TOLERANCE,
Expand Down
64 changes: 32 additions & 32 deletions src/ipc/collision_mesh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@ class CollisionMesh {
CollisionMesh() = default;

/// @brief Construct a new Collision Mesh object directly from the collision mesh vertices.
/// @param rest_positions The vertices of the collision mesh at rest (#V × dim).
/// @param edges The edges of the collision mesh (#E × 2).
/// @param faces The faces of the collision mesh (#F × 3).
/// @param rest_positions The vertices of the collision mesh at rest (|V| × dim).
/// @param edges The edges of the collision mesh (|E| × 2).
/// @param faces The faces of the collision mesh (|F| × 3).
/// @param displacement_map The displacement mapping from displacements on the full mesh to the collision mesh.
CollisionMesh(
Eigen::ConstRef<Eigen::MatrixXd> rest_positions,
Expand All @@ -26,9 +26,9 @@ class CollisionMesh {

/// @brief Construct a new Collision Mesh object from a full mesh vertices.
/// @param include_vertex Vector of bools indicating whether each vertex should be included in the collision mesh.
/// @param full_rest_positions The vertices of the full mesh at rest (#V × dim).
/// @param edges The edges of the collision mesh indexed into the full mesh vertices (#E × 2).
/// @param faces The faces of the collision mesh indexed into the full mesh vertices (#F × 3).
/// @param full_rest_positions The vertices of the full mesh at rest (|V| × dim).
/// @param edges The edges of the collision mesh indexed into the full mesh vertices (|E| × 2).
/// @param faces The faces of the collision mesh indexed into the full mesh vertices (|F| × 3).
/// @param displacement_map The displacement mapping from displacements on the full mesh to the collision mesh.
CollisionMesh(
const std::vector<bool>& include_vertex,
Expand All @@ -39,9 +39,9 @@ class CollisionMesh {
Eigen::SparseMatrix<double>());

/// @brief Helper function that automatically builds include_vertex using construct_is_on_surface.
/// @param full_rest_positions The full vertices at rest (#FV × dim).
/// @param edges The edge matrix of mesh (#E × 2).
/// @param faces The face matrix of mesh (#F × 3).
/// @param full_rest_positions The full vertices at rest (|FV| × dim).
/// @param edges The edge matrix of mesh (|E| × 2).
/// @param faces The face matrix of mesh (|F| × 3).
/// @return Constructed CollisionMesh.
static CollisionMesh build_from_full_mesh(
Eigen::ConstRef<Eigen::MatrixXd> full_rest_positions,
Expand Down Expand Up @@ -91,22 +91,22 @@ class CollisionMesh {
/// @brief Get the number of degrees of freedom in the full mesh.
size_t full_ndof() const { return full_num_vertices() * dim(); }

/// @brief Get the vertices of the collision mesh at rest (#V × dim).
/// @brief Get the vertices of the collision mesh at rest (|V| × dim).
const Eigen::MatrixXd& rest_positions() const { return m_rest_positions; }

/// @brief Get the indices of codimensional vertices of the collision mesh (#CV x 1).
/// @brief Get the indices of codimensional vertices of the collision mesh (|CV| x 1).
const Eigen::VectorXi& codim_vertices() const { return m_codim_vertices; }

/// @brief Get the indices of codimensional edges of the collision mesh (#CE x 1).
/// @brief Get the indices of codimensional edges of the collision mesh (|CE| x 1).
const Eigen::VectorXi& codim_edges() const { return m_codim_edges; }

/// @brief Get the edges of the collision mesh (#E × 2).
/// @brief Get the edges of the collision mesh (|E| × 2).
const Eigen::MatrixXi& edges() const { return m_edges; }

/// @brief Get the faces of the collision mesh (#F × 3).
/// @brief Get the faces of the collision mesh (|F| × 3).
const Eigen::MatrixXi& faces() const { return m_faces; }

/// @brief Get the mapping from faces to edges of the collision mesh (#F × 3).
/// @brief Get the mapping from faces to edges of the collision mesh (|F| × 3).
const Eigen::MatrixXi& faces_to_edges() const { return m_faces_to_edges; }

// const std::vector<std::vector<int>>& vertices_to_edges() const
Expand All @@ -122,20 +122,20 @@ class CollisionMesh {
// -----------------------------------------------------------------------

/// @brief Compute the vertex positions from the positions of the full mesh.
/// @param full_positions The vertex positions of the full mesh (#FV × dim).
/// @return The vertex positions of the collision mesh (#V × dim).
/// @param full_positions The vertex positions of the full mesh (|FV| × dim).
/// @return The vertex positions of the collision mesh (|V| × dim).
Eigen::MatrixXd
vertices(Eigen::ConstRef<Eigen::MatrixXd> full_positions) const;

/// @brief Compute the vertex positions from vertex displacements on the full mesh.
/// @param full_displacements The vertex displacements on the full mesh (#FV × dim).
/// @return The vertex positions of the collision mesh (#V × dim).
/// @param full_displacements The vertex displacements on the full mesh (|FV| × dim).
/// @return The vertex positions of the collision mesh (|V| × dim).
Eigen::MatrixXd displace_vertices(
Eigen::ConstRef<Eigen::MatrixXd> full_displacements) const;

/// @brief Map vertex displacements on the full mesh to vertex displacements on the collision mesh.
/// @param full_displacements The vertex displacements on the full mesh (#FV × dim).
/// @return The vertex displacements on the collision mesh (#V × dim).
/// @param full_displacements The vertex displacements on the full mesh (|FV| × dim).
/// @return The vertex displacements on the collision mesh (|V| × dim).
Eigen::MatrixXd map_displacements(
Eigen::ConstRef<Eigen::MatrixXd> full_displacements) const;

Expand Down Expand Up @@ -263,17 +263,17 @@ class CollisionMesh {

/// @brief Construct a vector of bools indicating whether each vertex is on the surface.
/// @param num_vertices The number of vertices in the mesh.
/// @param edges The surface edges of the mesh (#E × 2).
/// @param codim_vertices The indices of codimensional vertices (#CV x 1).
/// @param edges The surface edges of the mesh (|E| × 2).
/// @param codim_vertices The indices of codimensional vertices (|CV| x 1).
/// @return A vector of bools indicating whether each vertex is on the surface.
static std::vector<bool> construct_is_on_surface(
const size_t num_vertices,
Eigen::ConstRef<Eigen::MatrixXi> edges,
Eigen::ConstRef<Eigen::VectorXi> codim_vertices = Eigen::VectorXi());

/// @brief Construct a matrix that maps from the faces' edges to rows in the edges matrix.
/// @param faces The face matrix of mesh (#F × 3).
/// @param edges The edge matrix of mesh (#E × 2).
/// @param faces The face matrix of mesh (|F| × 3).
/// @param edges The edge matrix of mesh (|E| × 2).
/// @return Matrix that maps from the faces' edges to rows in the edges matrix.
static Eigen::MatrixXi construct_faces_to_edges(
Eigen::ConstRef<Eigen::MatrixXi> faces,
Expand Down Expand Up @@ -303,19 +303,19 @@ class CollisionMesh {

// -----------------------------------------------------------------------

/// @brief The full vertex positions at rest (#FV × dim).
/// @brief The full vertex positions at rest (|FV| × dim).
Eigen::MatrixXd m_full_rest_positions;
/// @brief The vertex positions at rest (#V × dim).
/// @brief The vertex positions at rest (|V| × dim).
Eigen::MatrixXd m_rest_positions;
/// @brief The indices of codimensional vertices (#CV x 1).
/// @brief The indices of codimensional vertices (|CV| x 1).
Eigen::VectorXi m_codim_vertices;
/// @brief The indices of codimensional edges (#CE x 1).
/// @brief The indices of codimensional edges (|CE| x 1).
Eigen::VectorXi m_codim_edges;
/// @brief Edges as rows of indicies into vertices (#E × 2).
/// @brief Edges as rows of indicies into vertices (|E| × 2).
Eigen::MatrixXi m_edges;
/// @brief Triangular faces as rows of indicies into vertices (#F × 3).
/// @brief Triangular faces as rows of indicies into vertices (|F| × 3).
Eigen::MatrixXi m_faces;
/// @brief Map from faces edges to rows of edges (#F × 3).
/// @brief Map from faces edges to rows of edges (|F| × 3).
Eigen::MatrixXi m_faces_to_edges;

/// @brief Map from full vertices to collision vertices.
Expand Down
2 changes: 1 addition & 1 deletion src/ipc/collisions/normal/normal_collisions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class NormalCollisions {
/// @param vertices Vertices of the collision mesh.
/// @param dhat The activation distance of the barrier.
/// @param dmin Minimum distance.
/// @param broad_phase_method Broad-phase method to use.
/// @param broad_phase Broad-phase method to use.
void build(
const CollisionMesh& mesh,
Eigen::ConstRef<Eigen::MatrixXd> vertices,
Expand Down
12 changes: 6 additions & 6 deletions src/ipc/distance/line_line.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@ namespace ipc {
/// @warning If the lines are parallel this function returns a distance of zero.
/// @param ea0 The first vertex of the edge defining the first line.
/// @param ea1 The second vertex of the edge defining the first line.
/// @param ea0 The first vertex of the edge defining the second line.
/// @param ea1 The second vertex of the edge defining the second line.
/// @param eb0 The first vertex of the edge defining the second line.
/// @param eb1 The second vertex of the edge defining the second line.
/// @return The distance between the two lines.
double line_line_distance(
Eigen::ConstRef<Eigen::Vector3d> ea0,
Expand All @@ -23,8 +23,8 @@ double line_line_distance(
/// @warning If the lines are parallel this function returns a distance of zero.
/// @param ea0 The first vertex of the edge defining the first line.
/// @param ea1 The second vertex of the edge defining the first line.
/// @param ea0 The first vertex of the edge defining the second line.
/// @param ea1 The second vertex of the edge defining the second line.
/// @param eb0 The first vertex of the edge defining the second line.
/// @param eb1 The second vertex of the edge defining the second line.
/// @return The gradient of the distance wrt ea0, ea1, eb0, and eb1.
Vector12d line_line_distance_gradient(
Eigen::ConstRef<Eigen::Vector3d> ea0,
Expand All @@ -37,8 +37,8 @@ Vector12d line_line_distance_gradient(
/// @warning If the lines are parallel this function returns a distance of zero.
/// @param ea0 The first vertex of the edge defining the first line.
/// @param ea1 The second vertex of the edge defining the first line.
/// @param ea0 The first vertex of the edge defining the second line.
/// @param ea1 The second vertex of the edge defining the second line.
/// @param eb0 The first vertex of the edge defining the second line.
/// @param eb1 The second vertex of the edge defining the second line.
/// @return The hessian of the distance wrt ea0, ea1, eb0, and eb1.
Matrix12d line_line_distance_hessian(
Eigen::ConstRef<Eigen::Vector3d> ea0,
Expand Down
Loading