From b2c5d1d38d9a6705d08f63af520ba76368044a9c Mon Sep 17 00:00:00 2001 From: ManifoldFR Date: Mon, 18 Dec 2023 17:44:21 +0100 Subject: [PATCH 1/2] [cmake | core | python] Change all macros & compile definitions prefixed by PROXNLP_ to PROXSUITE_NLP_ + rename macro PROXNLP_ENABLE_PROXSUITE_LDLT to PROXSUITE_NLP_ENABLE_PROXSUITE_LDLT --- CMakeLists.txt | 16 ++--- doc/Doxyfile.extra.in | 2 +- examples/ur5-ik.cpp | 2 +- include/proxnlp/constraint-base.hpp | 4 +- include/proxnlp/context.hpp | 2 +- include/proxnlp/cost-function.hpp | 8 +-- include/proxnlp/cost-sum.hpp | 4 +- include/proxnlp/exceptions.hpp | 15 ++-- include/proxnlp/function-base.hpp | 8 +-- include/proxnlp/function-ops.hpp | 6 +- include/proxnlp/helpers/history-callback.hpp | 2 +- include/proxnlp/ldlt-allocator.hpp | 10 +-- include/proxnlp/linalg/block-ldlt.hpp | 6 +- include/proxnlp/linalg/block-ldlt.hxx | 4 +- include/proxnlp/linalg/dense.hpp | 2 +- include/proxnlp/linalg/gemmt.hpp | 70 +++++++++---------- include/proxnlp/linalg/ldlt-base.hpp | 6 +- .../proxnlp/linalg/proxsuite-ldlt-wrap.hpp | 2 +- include/proxnlp/linesearch-armijo.hpp | 2 +- include/proxnlp/linesearch-base.hpp | 2 +- include/proxnlp/macros.hpp | 18 ++--- include/proxnlp/manifold-base.hpp | 8 +-- include/proxnlp/math.hpp | 4 +- .../modelling/autodiff/finite-difference.hpp | 8 +-- include/proxnlp/modelling/constraints.hpp | 2 +- .../modelling/constraints/box-constraint.hpp | 2 +- .../constraints/equality-constraint.hpp | 2 +- .../modelling/constraints/l1-penalty.hpp | 2 +- .../constraints/negative-orthant.hpp | 2 +- .../modelling/costs/quadratic-residual.hpp | 4 +- .../modelling/costs/quadratic-residual.hxx | 4 +- .../modelling/costs/squared-distance.hpp | 4 +- .../proxnlp/modelling/residuals/linear.hpp | 6 +- .../residuals/rigid-transform-point.hpp | 4 +- .../modelling/residuals/state-residual.hpp | 4 +- .../modelling/spaces/cartesian-product.hpp | 4 +- .../modelling/spaces/cartesian-product.hxx | 4 +- .../proxnlp/modelling/spaces/multibody.hpp | 4 +- .../modelling/spaces/pinocchio-groups.hpp | 2 +- include/proxnlp/modelling/spaces/sphere.hpp | 2 +- .../modelling/spaces/tangent-bundle.hpp | 10 +-- .../proxnlp/modelling/spaces/vector-space.hpp | 2 +- include/proxnlp/pdal.hpp | 4 +- include/proxnlp/problem-base.hpp | 4 +- include/proxnlp/prox-solver.hpp | 6 +- include/proxnlp/prox-solver.hxx | 39 ++++++----- include/proxnlp/results.hpp | 4 +- include/proxnlp/workspace.hpp | 4 +- python/expose-cost.cpp | 2 +- python/expose-ldlt.cpp | 2 +- python/expose-manifold.cpp | 6 +- python/expose-pinocchio-residuals.cpp | 2 +- python/function.hpp | 6 +- python/fwd.hpp | 2 +- python/module.cpp | 4 +- tests/cholesky-block-sparse-bench.cpp | 2 +- tests/cholesky-block-sparse.cpp | 2 +- tests/constraints.cpp | 2 +- tests/costs.cpp | 6 +- tests/finite-diff.cpp | 6 +- tests/manifolds.cpp | 4 +- tests/util.hpp | 2 +- 62 files changed, 193 insertions(+), 191 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7a138b18..e54db41f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -85,12 +85,12 @@ endif(INITIALIZE_WITH_NAN) if(CHECK_RUNTIME_MALLOC) message(STATUS "Check if some memory allocations are performed at runtime.") - add_compile_definitions(PROXNLP_EIGEN_CHECK_MALLOC) + add_compile_definitions(PROXSUITE_NLP_EIGEN_CHECK_MALLOC) add_definitions(-DEIGEN_RUNTIME_NO_MALLOC) endif(CHECK_RUNTIME_MALLOC) if(ENABLE_TEMPLATE_INSTANTIATION) - add_definitions(-DPROXNLP_ENABLE_TEMPLATE_INSTANTIATION) + add_definitions(-DPROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION) endif(ENABLE_TEMPLATE_INSTANTIATION) macro(TAG_LIBRARY_VERSION target) @@ -105,7 +105,7 @@ add_project_dependency(fmt "9.1.0...<11" REQUIRED PKG_CONFIG_REQUIRES "fmt >= 9. if(BUILD_WITH_PROXSUITE) add_project_dependency(proxsuite REQUIRED) - add_definitions(-DPROXNLP_ENABLE_PROXSUITE_LDLT) + add_definitions(-DPROXSUITE_NLP_USE_PROXSUITE_LDLT) endif() # Variable containing all the cflags definition relative to optional dependencies @@ -113,7 +113,7 @@ set(CFLAGS_DEPENDENCIES) if(BUILD_WITH_OPENMP_SUPPORT) find_package(OpenMP REQUIRED) - add_compile_definitions(PROXNLP_MULTITHREADING) + add_compile_definitions(PROXSUITE_NLP_MULTITHREADING) endif(BUILD_WITH_OPENMP_SUPPORT) set(BOOST_REQUIRED_COMPONENTS filesystem serialization system) @@ -137,7 +137,7 @@ endif(BUILD_PYTHON_INTERFACE) if(BUILD_WITH_PINOCCHIO_SUPPORT) message(STATUS "Building with Pinocchio support.") add_project_dependency(pinocchio REQUIRED PKG_CONFIG_REQUIRES "pinocchio >= 2.9.1") - add_compile_definitions(PROXNLP_WITH_PINOCCHIO) + add_compile_definitions(PROXSUITE_NLP_WITH_PINOCCHIO) endif(BUILD_WITH_PINOCCHIO_SUPPORT) # --- MAIN LIBRARY ---------------------------------------- @@ -278,13 +278,13 @@ endmacro( var_value) if(BUILD_WITH_PINOCCHIO_SUPPORT) - export_variable(PROXNLP_WITH_PINOCCHIO_SUPPORT ON) + export_variable(PROXSUITE_NLP_WITH_PINOCCHIO_SUPPORT ON) endif() if(BUILD_WITH_CASADI_SUPPORT) - export_variable(PROXNLP_USE_CASADI ON) + export_variable(PROXSUITE_NLP_USE_CASADI ON) endif() if(BUILD_PYTHON_INTERFACE) - export_variable(PROXNLP_WITH_PYTHON_INTERFACE ON) + export_variable(PROXSUITE_NLP_WITH_PYTHON_INTERFACE ON) endif() pkg_config_append_libs(${PROJECT_NAME}) diff --git a/doc/Doxyfile.extra.in b/doc/Doxyfile.extra.in index 75e97017..93503bd5 100644 --- a/doc/Doxyfile.extra.in +++ b/doc/Doxyfile.extra.in @@ -20,7 +20,7 @@ ENABLE_PREPROCESSING = YES MACRO_EXPANSION = YES EXPAND_ONLY_PREDEF = YES PREDEFINED += EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ - PROXNLP_DYNAMIC_TYPEDEFS + PROXSUITE_NLP_DYNAMIC_TYPEDEFS FULL_PATH_NAMES = YES EXCLUDE_SYMBOLS = *::internal, internal::*, *::internal::* diff --git a/examples/ur5-ik.cpp b/examples/ur5-ik.cpp index 793b790d..17b1474f 100644 --- a/examples/ur5-ik.cpp +++ b/examples/ur5-ik.cpp @@ -15,7 +15,7 @@ #include using Scalar = double; -PROXNLP_DYNAMIC_TYPEDEFS(Scalar); +PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using namespace proxnlp; namespace pin = pinocchio; diff --git a/include/proxnlp/constraint-base.hpp b/include/proxnlp/constraint-base.hpp index d9af2586..c54bba18 100644 --- a/include/proxnlp/constraint-base.hpp +++ b/include/proxnlp/constraint-base.hpp @@ -16,7 +16,7 @@ namespace proxnlp { template struct ConstraintSetBase { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using ActiveType = Eigen::Matrix; using Self = ConstraintSetBase; @@ -117,7 +117,7 @@ template struct ConstraintSetBase { */ template struct ConstraintObjectTpl { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using FunctionType = C2FunctionTpl; using ConstraintSet = ConstraintSetBase; diff --git a/include/proxnlp/context.hpp b/include/proxnlp/context.hpp index 189b7e82..8d98b4ac 100644 --- a/include/proxnlp/context.hpp +++ b/include/proxnlp/context.hpp @@ -7,7 +7,7 @@ namespace context { using Scalar = double; -PROXNLP_DYNAMIC_TYPEDEFS(Scalar); +PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using VectorXBool = Eigen::Matrix; using BCLParams = ::proxnlp::BCLParamsTpl; diff --git a/include/proxnlp/cost-function.hpp b/include/proxnlp/cost-function.hpp index e35b1641..1697cf8d 100644 --- a/include/proxnlp/cost-function.hpp +++ b/include/proxnlp/cost-function.hpp @@ -14,7 +14,7 @@ template auto downcast_function_to_cost(const shared_ptr> &func) -> shared_ptr> { if (func->nr() != 1) { - PROXNLP_RUNTIME_ERROR( + PROXSUITE_NLP_RUNTIME_ERROR( "Function cannot be cast to cost (codimension nr != 1)."); } return std::make_shared>(func); @@ -29,7 +29,7 @@ template struct CostFunctionBaseTpl : public C2FunctionTpl<_Scalar> { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = C2FunctionTpl; CostFunctionBaseTpl(const int nx, const int ndx) : Base(nx, ndx, 1) {} @@ -90,7 +90,7 @@ struct CostFunctionBaseTpl : public C2FunctionTpl<_Scalar> { template struct func_to_cost : CostFunctionBaseTpl<_Scalar> { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = CostFunctionBaseTpl; using C2Function = C2FunctionTpl; @@ -118,6 +118,6 @@ template struct func_to_cost : CostFunctionBaseTpl<_Scalar> { } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/cost-function.txx" #endif diff --git a/include/proxnlp/cost-sum.hpp b/include/proxnlp/cost-sum.hpp index 10179bdd..6e9929d3 100644 --- a/include/proxnlp/cost-sum.hpp +++ b/include/proxnlp/cost-sum.hpp @@ -11,7 +11,7 @@ namespace proxnlp { template struct CostSumTpl : CostFunctionBaseTpl<_Scalar> { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = CostFunctionBaseTpl; using BasePtr = shared_ptr; @@ -114,6 +114,6 @@ template struct CostSumTpl : CostFunctionBaseTpl<_Scalar> { #include "proxnlp/cost-sum.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/cost-sum.txx" #endif diff --git a/include/proxnlp/exceptions.hpp b/include/proxnlp/exceptions.hpp index 4cc1d228..f13314b2 100644 --- a/include/proxnlp/exceptions.hpp +++ b/include/proxnlp/exceptions.hpp @@ -5,22 +5,23 @@ #include #include -#define PROXNLP_RUNTIME_ERROR(msg) \ +#define PROXSUITE_NLP_RUNTIME_ERROR(msg) \ throw ::proxnlp::RuntimeError( \ fmt::format("{}({}): {}", __FILE__, __LINE__, msg)) -#define PROXNLP_DIM_CHECK(x, nx) \ +#define PROXSUITE_NLP_DIM_CHECK(x, nx) \ if (x.size() != nx) \ - PROXNLP_RUNTIME_ERROR(fmt::format( \ + PROXSUITE_NLP_RUNTIME_ERROR(fmt::format( \ "Input size invalid (expected {:d}, got {:d})", nx, x.size())) -#define PROXNLP_RAISE_IF_NAN(value) \ +#define PROXSUITE_NLP_RAISE_IF_NAN(value) \ if (::proxnlp::math::check_value(value)) \ - PROXNLP_RUNTIME_ERROR("Encountered NaN.\n") + PROXSUITE_NLP_RUNTIME_ERROR("Encountered NaN.\n") -#define PROXNLP_RAISE_IF_NAN_NAME(value, name) \ +#define PROXSUITE_NLP_RAISE_IF_NAN_NAME(value, name) \ if (::proxnlp::math::check_value(value)) \ - PROXNLP_RUNTIME_ERROR(fmt::format("Encountered NaN for value {:s}.\n", name)) + PROXSUITE_NLP_RUNTIME_ERROR( \ + fmt::format("Encountered NaN for value {:s}.\n", name)) namespace proxnlp { diff --git a/include/proxnlp/function-base.hpp b/include/proxnlp/function-base.hpp index 3a38d20c..191bdaea 100644 --- a/include/proxnlp/function-base.hpp +++ b/include/proxnlp/function-base.hpp @@ -17,7 +17,7 @@ template struct BaseFunctionTpl : math_types<_Scalar> { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); BaseFunctionTpl(const int nx, const int ndx, const int nr) : nx_(nx), ndx_(ndx), nr_(nr) {} @@ -46,7 +46,7 @@ struct C1FunctionTpl : public BaseFunctionTpl<_Scalar> { using Scalar = _Scalar; using Base = BaseFunctionTpl<_Scalar>; using Base::Base; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); /// @brief Jacobian matrix of the constraint function. virtual void computeJacobian(const ConstVectorRef &x, @@ -72,7 +72,7 @@ struct C2FunctionTpl : public C1FunctionTpl<_Scalar> { using Scalar = _Scalar; using Base = C1FunctionTpl<_Scalar>; using Base::Base; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); /// @brief Vector-hessian product. virtual void vectorHessianProduct(const ConstVectorRef &, @@ -84,6 +84,6 @@ struct C2FunctionTpl : public C1FunctionTpl<_Scalar> { } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/function-base.txx" #endif diff --git a/include/proxnlp/function-ops.hpp b/include/proxnlp/function-ops.hpp index b7c49b7f..f3940865 100644 --- a/include/proxnlp/function-ops.hpp +++ b/include/proxnlp/function-ops.hpp @@ -17,14 +17,14 @@ template struct ComposeFunctionTpl : C2FunctionTpl<_Scalar> { using Base::computeJacobian; using Base::vectorHessianProduct; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); ComposeFunctionTpl(const shared_ptr &left, const shared_ptr &right) : Base(right->nx(), right->ndx(), left->nr()), left_(left), right_(right) { if (left->nx() != right->nr()) { - PROXNLP_RUNTIME_ERROR(fmt::format( + PROXSUITE_NLP_RUNTIME_ERROR(fmt::format( "Incompatible dimensions ({:d} and {:d}).", left->nx(), right->nr())); } assert(left->nx() == right->nr()); @@ -59,6 +59,6 @@ auto compose(const shared_ptr> &left, } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/function-ops.txx" #endif diff --git a/include/proxnlp/helpers/history-callback.hpp b/include/proxnlp/helpers/history-callback.hpp index 6502bf7e..d7c59a08 100644 --- a/include/proxnlp/helpers/history-callback.hpp +++ b/include/proxnlp/helpers/history-callback.hpp @@ -17,7 +17,7 @@ template struct history_callback : base_callback { : store_primal_dual_vars_(store_pd_vars), store_values_(store_values), store_residuals_(store_residuals) {} - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); struct { std::vector xs; diff --git a/include/proxnlp/ldlt-allocator.hpp b/include/proxnlp/ldlt-allocator.hpp index 95a27aaa..5ba79b99 100644 --- a/include/proxnlp/ldlt-allocator.hpp +++ b/include/proxnlp/ldlt-allocator.hpp @@ -6,7 +6,7 @@ #include "proxnlp/linalg/block-ldlt.hpp" #include "proxnlp/linalg/bunchkaufman.hpp" -#ifdef PROXNLP_ENABLE_PROXSUITE_LDLT +#ifdef PROXSUITE_NLP_USE_PROXSUITE_LDLT #include "proxnlp/linalg/proxsuite-ldlt-wrap.hpp" #endif #include @@ -36,7 +36,7 @@ template , linalg::BlockLDLT, Eigen::LDLT, Eigen::BunchKaufman -#ifdef PROXNLP_ENABLE_PROXSUITE_LDLT +#ifdef PROXSUITE_NLP_USE_PROXSUITE_LDLT , linalg::ProxSuiteLDLTWrapper #endif @@ -119,10 +119,10 @@ LDLTVariant allocate_ldlt_from_sizes(const std::vector &nprims, case LDLTChoice::EIGEN: return Eigen::LDLT(size); case LDLTChoice::PROXSUITE: -#ifdef PROXNLP_ENABLE_PROXSUITE_LDLT +#ifdef PROXSUITE_NLP_USE_PROXSUITE_LDLT return linalg::ProxSuiteLDLTWrapper(size, size); #else - PROXNLP_RUNTIME_ERROR( + PROXSUITE_NLP_RUNTIME_ERROR( "ProxSuite support is not enabled. You should recompile ProxNLP with " "the BUILD_WITH_PROXSUITE flag."); #endif @@ -210,7 +210,7 @@ computeInertiaTuple(const Eigen::Ref &signature) { nn++; break; default: - PROXNLP_RUNTIME_ERROR( + PROXSUITE_NLP_RUNTIME_ERROR( "Signature vector should only contain values O, 1, -1."); break; } diff --git a/include/proxnlp/linalg/block-ldlt.hpp b/include/proxnlp/linalg/block-ldlt.hpp index caec6ca3..11b019a4 100644 --- a/include/proxnlp/linalg/block-ldlt.hpp +++ b/include/proxnlp/linalg/block-ldlt.hpp @@ -19,7 +19,7 @@ namespace backend { /// Implementation struct for the recursive block LDLT algorithm. template struct block_impl { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); MatrixRef mat; SymbolicBlockMatrix sym_structure; /// @returns bool whether the decomposition was successful. @@ -194,7 +194,7 @@ template struct block_impl { /// of structure should lead to recalculating the expected sparsity pattern of /// the factorization, and even recomputing the sparsity-optimal permutation. template struct BlockLDLT : ldlt_base { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ldlt_base; using DView = typename Base::DView; using Traits = LDLT_Traits; @@ -340,6 +340,6 @@ template struct BlockLDLT : ldlt_base { #include "./block-ldlt.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "./block-ldlt.txx" #endif diff --git a/include/proxnlp/linalg/block-ldlt.hxx b/include/proxnlp/linalg/block-ldlt.hxx index 4e00ede4..ac282dc4 100644 --- a/include/proxnlp/linalg/block-ldlt.hxx +++ b/include/proxnlp/linalg/block-ldlt.hxx @@ -73,7 +73,7 @@ template bool BlockLDLT::solveInPlace(Eigen::MatrixBase &b) const { b.noalias() = permutationP().transpose() * b; - PROXNLP_NOMALLOC_BEGIN; + PROXSUITE_NLP_NOMALLOC_BEGIN; BlockTriL mat_blk_L(m_matrix, m_structure); bool flag = mat_blk_L.solveInPlace(b); @@ -91,7 +91,7 @@ bool BlockLDLT::solveInPlace(Eigen::MatrixBase &b) const { BlockTriU mat_blk_U(m_matrix.transpose(), m_struct_tr); flag |= mat_blk_U.solveInPlace(b); - PROXNLP_NOMALLOC_END; + PROXSUITE_NLP_NOMALLOC_END; b.noalias() = permutationP() * b; return flag; } diff --git a/include/proxnlp/linalg/dense.hpp b/include/proxnlp/linalg/dense.hpp index 42fa11e6..074ba1af 100644 --- a/include/proxnlp/linalg/dense.hpp +++ b/include/proxnlp/linalg/dense.hpp @@ -161,7 +161,7 @@ dense_ldlt_reconstruct(typename math_types::ConstMatrixRef const &mat, /// @brief A fast, recursive divide-and-conquer LDLT algorithm. template struct DenseLDLT : ldlt_base { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ldlt_base; using DView = typename Base::DView; using MatrixType = MatrixXs; diff --git a/include/proxnlp/linalg/gemmt.hpp b/include/proxnlp/linalg/gemmt.hpp index e4d6d33a..05aaaca3 100644 --- a/include/proxnlp/linalg/gemmt.hpp +++ b/include/proxnlp/linalg/gemmt.hpp @@ -8,21 +8,21 @@ namespace proxnlp { namespace linalg { namespace backend { -#define PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) \ +#define PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) \ template \ static void fn(Eigen::MatrixBase &dst, \ Eigen::MatrixBase const &lhs, \ Eigen::MatrixBase const &rhs, Scalar alpha) template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); - PROXNLP_GEMMT_SIGNATURE(Scalar, /*dst*/, /*lhs*/, /*rhs*/, /*alpha*/) {} + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, /*dst*/, /*lhs*/, /*rhs*/, /*alpha*/) {} }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is diagonal - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { auto v = lhs.diagonal().cwiseProduct(rhs.transpose().diagonal()); isize n = v.rows(); dst.diagonal().head(n) += alpha * v; @@ -30,9 +30,9 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is triu - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // dst.template triangularView() += // alpha * (lhs.diagonal().asDiagonal() * // rhs.template triangularView().transpose()); @@ -47,9 +47,9 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is tril - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // dst.template triangularView() += // alpha * (lhs.diagonal().asDiagonal() * // rhs.template triangularView().transpose()); @@ -65,17 +65,17 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is dense - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst += alpha * (lhs.diagonal().asDiagonal() * rhs.transpose()); } }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is tril - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // dst.template triangularView() += // alpha * (lhs.template triangularView() * // rhs.diagonal().asDiagonal()); @@ -90,9 +90,9 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is dense - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // PERF // dst += alpha * (lhs.template triangularView() * // rhs.transpose().template @@ -103,9 +103,9 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is tril - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // PERF // dst += alpha * (lhs.template triangularView() * // rhs.transpose().template @@ -116,18 +116,18 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is dense - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst.noalias() += lhs.template triangularView() * (alpha * rhs.transpose()); } }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is triu - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // dst.template triangularView() += // alpha * (lhs.template triangularView() * // rhs.diagonal().asDiagonal()); @@ -141,9 +141,9 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is triu - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // PERF // dst.template triangularView() += // alpha * (lhs.template triangularView() * @@ -154,9 +154,9 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is dense - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { // PERF // dst.noalias() += alpha * (lhs.template triangularView() * // rhs.transpose().template @@ -167,40 +167,40 @@ template struct GemmT { }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // dst is dense - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst.noalias() += (lhs.template triangularView() * (alpha * rhs.transpose())); } }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst.noalias() += alpha * (lhs * rhs.transpose().diagonal().asDiagonal()); } }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst.noalias() += alpha * (lhs * rhs.transpose().template triangularView()); } }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst.noalias() += alpha * (lhs * rhs.transpose().template triangularView()); } }; template struct GemmT { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); - PROXNLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_GEMMT_SIGNATURE(Scalar, dst, lhs, rhs, alpha) { dst.noalias() += alpha * lhs * rhs.transpose(); } }; diff --git a/include/proxnlp/linalg/ldlt-base.hpp b/include/proxnlp/linalg/ldlt-base.hpp index 1a5d6ed6..ca838267 100644 --- a/include/proxnlp/linalg/ldlt-base.hpp +++ b/include/proxnlp/linalg/ldlt-base.hpp @@ -21,7 +21,7 @@ using Eigen::internal::SignMatrix; /// @brief Base interface for LDLT solvers. template struct ldlt_base { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using DView = Eigen::Map>; @@ -32,11 +32,11 @@ template struct ldlt_base { virtual ldlt_base &compute(const ConstMatrixRef &mat) = 0; bool solveInPlace(MatrixRef) const { - PROXNLP_RUNTIME_ERROR("Not implemented"); + PROXSUITE_NLP_RUNTIME_ERROR("Not implemented"); } virtual DView vectorD() const = 0; virtual const MatrixXs &matrixLDLT() const { - PROXNLP_RUNTIME_ERROR("Not implemented"); + PROXSUITE_NLP_RUNTIME_ERROR("Not implemented"); } virtual MatrixXs reconstructedMatrix() const = 0; Eigen::ComputationInfo info() const { return m_info; } diff --git a/include/proxnlp/linalg/proxsuite-ldlt-wrap.hpp b/include/proxnlp/linalg/proxsuite-ldlt-wrap.hpp index 1a56c22f..026952e3 100644 --- a/include/proxnlp/linalg/proxsuite-ldlt-wrap.hpp +++ b/include/proxnlp/linalg/proxsuite-ldlt-wrap.hpp @@ -44,7 +44,7 @@ namespace linalg { /// @brief Use the LDLT from proxsuite. template struct ProxSuiteLDLTWrapper : ldlt_base { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ldlt_base; using psldlt_t = psdense::Ldlt; using DView = typename Base::DView; diff --git a/include/proxnlp/linesearch-armijo.hpp b/include/proxnlp/linesearch-armijo.hpp index 7c4d6587..bbf30397 100644 --- a/include/proxnlp/linesearch-armijo.hpp +++ b/include/proxnlp/linesearch-armijo.hpp @@ -109,7 +109,7 @@ class ArmijoLinesearch final : public Linesearch { break; } default: - PROXNLP_RUNTIME_ERROR( + PROXSUITE_NLP_RUNTIME_ERROR( "Unrecognized interpolation type in this context.\n"); break; } diff --git a/include/proxnlp/linesearch-base.hpp b/include/proxnlp/linesearch-base.hpp index 67d6c5b4..974df3bd 100644 --- a/include/proxnlp/linesearch-base.hpp +++ b/include/proxnlp/linesearch-base.hpp @@ -72,6 +72,6 @@ template Linesearch::~Linesearch() = default; #include "proxnlp/linesearch-armijo.hpp" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/linesearch.txx" #endif diff --git a/include/proxnlp/macros.hpp b/include/proxnlp/macros.hpp index 485d3e97..16a46092 100644 --- a/include/proxnlp/macros.hpp +++ b/include/proxnlp/macros.hpp @@ -3,25 +3,25 @@ #pragma once /// @brief Macro empty arg -#define PROXNLP_MACRO_EMPTY_ARG +#define PROXSUITE_NLP_MACRO_EMPTY_ARG -#define PROXNLP_EIGEN_CONST_CAST(type, obj) const_cast(obj) +#define PROXSUITE_NLP_EIGEN_CONST_CAST(type, obj) const_cast(obj) -#ifdef PROXNLP_EIGEN_CHECK_MALLOC -#define PROXNLP_EIGEN_ALLOW_MALLOC(allowed) \ +#ifdef PROXSUITE_NLP_EIGEN_CHECK_MALLOC +#define PROXSUITE_NLP_EIGEN_ALLOW_MALLOC(allowed) \ ::Eigen::internal::set_is_malloc_allowed(allowed) #else -#define PROXNLP_EIGEN_ALLOW_MALLOC(allowed) +#define PROXSUITE_NLP_EIGEN_ALLOW_MALLOC(allowed) #endif /// @brief Entering performance-critical code. -#define PROXNLP_NOMALLOC_BEGIN PROXNLP_EIGEN_ALLOW_MALLOC(false) +#define PROXSUITE_NLP_NOMALLOC_BEGIN PROXSUITE_NLP_EIGEN_ALLOW_MALLOC(false) /// @brief Exiting performance-critical code. -#define PROXNLP_NOMALLOC_END PROXNLP_EIGEN_ALLOW_MALLOC(true) +#define PROXSUITE_NLP_NOMALLOC_END PROXSUITE_NLP_EIGEN_ALLOW_MALLOC(true) #ifdef __GNUC__ -#define PROXNLP_INLINE inline __attribute__((always_inline)) +#define PROXSUITE_NLP_INLINE inline __attribute__((always_inline)) #else -#define PROXNLP_INLINE inline +#define PROXSUITE_NLP_INLINE inline #endif diff --git a/include/proxnlp/manifold-base.hpp b/include/proxnlp/manifold-base.hpp index 23002fdd..c60e1464 100644 --- a/include/proxnlp/manifold-base.hpp +++ b/include/proxnlp/manifold-base.hpp @@ -7,8 +7,8 @@ namespace proxnlp { /// Macro which brings manifold typedefs up into the constraint, cost type, etc. -#define PROXNLP_DEFINE_MANIFOLD_TYPES(M) \ - PROXNLP_DYNAMIC_TYPEDEFS(typename M::Scalar); \ +#define PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(M) \ + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(typename M::Scalar); \ using PointType = typename M::PointType; \ using TangentVectorType = typename M::TangentVectorType; @@ -20,7 +20,7 @@ template struct ManifoldAbstractTpl { using Scalar = _Scalar; /// Scalar type enum { Options = _Options }; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using PointType = Eigen::Matrix; using TangentVectorType = Eigen::Matrix; @@ -137,6 +137,6 @@ template struct ManifoldAbstractTpl { #include "proxnlp/manifold-base.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/manifold-base.txx" #endif diff --git a/include/proxnlp/math.hpp b/include/proxnlp/math.hpp index c8d1fd77..e66ae198 100644 --- a/include/proxnlp/math.hpp +++ b/include/proxnlp/math.hpp @@ -22,7 +22,7 @@ using enable_if_eigen_dense = std::enable_if_t, T2>; /// Macro typedefs for dynamic-sized vectors/matrices, used for cost funcs, /// merit funcs because we don't CRTP them and virtual members funcs can't be /// templated. -#define PROXNLP_DYNAMIC_TYPEDEFS(Scalar) \ +#define PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar) \ using VectorXs = Eigen::Matrix; \ using MatrixXs = Eigen::Matrix; \ using VectorOfVectors = std::vector; \ @@ -41,7 +41,7 @@ using enable_if_eigen_dense = std::enable_if_t, T2>; /// type. template struct math_types { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(_Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(_Scalar); }; /// Math utilities diff --git a/include/proxnlp/modelling/autodiff/finite-difference.hpp b/include/proxnlp/modelling/autodiff/finite-difference.hpp index 21fc0e00..0955ab79 100644 --- a/include/proxnlp/modelling/autodiff/finite-difference.hpp +++ b/include/proxnlp/modelling/autodiff/finite-difference.hpp @@ -28,7 +28,7 @@ struct finite_difference_impl; template struct finite_difference_impl : virtual C1FunctionTpl { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using FuncType = BaseFunctionTpl; using Base = C1FunctionTpl; using Base::computeJacobian; @@ -59,7 +59,7 @@ struct finite_difference_impl : virtual C1FunctionTpl { template struct finite_difference_impl : virtual C2FunctionTpl { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using FuncType = C1FunctionTpl; using Base = C2FunctionTpl; using Base::vectorHessianProduct; @@ -114,7 +114,7 @@ struct finite_difference_wrapper<_Scalar, TOC1> using Base = internal::finite_difference_impl; using Base::computeJacobian; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); finite_difference_wrapper(const ManifoldAbstractTpl &space, const InputType &func, const Scalar fd_eps) @@ -143,7 +143,7 @@ struct finite_difference_wrapper<_Scalar, TOC2> using Base1::computeJacobian; using Base2::vectorHessianProduct; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); finite_difference_wrapper(const ManifoldAbstractTpl &space, const InputType &func, const Scalar fd_eps) diff --git a/include/proxnlp/modelling/constraints.hpp b/include/proxnlp/modelling/constraints.hpp index e9c83e88..368b25a2 100644 --- a/include/proxnlp/modelling/constraints.hpp +++ b/include/proxnlp/modelling/constraints.hpp @@ -5,7 +5,7 @@ #include "proxnlp/modelling/constraints/box-constraint.hpp" #include "proxnlp/modelling/constraints/l1-penalty.hpp" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/context.hpp" namespace proxnlp { diff --git a/include/proxnlp/modelling/constraints/box-constraint.hpp b/include/proxnlp/modelling/constraints/box-constraint.hpp index dbeac4f1..f289539a 100644 --- a/include/proxnlp/modelling/constraints/box-constraint.hpp +++ b/include/proxnlp/modelling/constraints/box-constraint.hpp @@ -10,7 +10,7 @@ namespace proxnlp { * */ template struct BoxConstraintTpl : ConstraintSetBase { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ConstraintSetBase; using ActiveType = typename Base::ActiveType; diff --git a/include/proxnlp/modelling/constraints/equality-constraint.hpp b/include/proxnlp/modelling/constraints/equality-constraint.hpp index 8f0f870d..00024581 100644 --- a/include/proxnlp/modelling/constraints/equality-constraint.hpp +++ b/include/proxnlp/modelling/constraints/equality-constraint.hpp @@ -15,7 +15,7 @@ template struct EqualityConstraint : ConstraintSetBase<_Scalar> { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ConstraintSetBase; using ActiveType = typename Base::ActiveType; diff --git a/include/proxnlp/modelling/constraints/l1-penalty.hpp b/include/proxnlp/modelling/constraints/l1-penalty.hpp index b576d0e9..5866b090 100644 --- a/include/proxnlp/modelling/constraints/l1-penalty.hpp +++ b/include/proxnlp/modelling/constraints/l1-penalty.hpp @@ -16,7 +16,7 @@ namespace proxnlp { template struct NonsmoothPenaltyL1Tpl : ConstraintSetBase<_Scalar> { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ConstraintSetBase; using ActiveType = typename Base::ActiveType; diff --git a/include/proxnlp/modelling/constraints/negative-orthant.hpp b/include/proxnlp/modelling/constraints/negative-orthant.hpp index 4c8b220c..3f4810d2 100644 --- a/include/proxnlp/modelling/constraints/negative-orthant.hpp +++ b/include/proxnlp/modelling/constraints/negative-orthant.hpp @@ -17,7 +17,7 @@ namespace proxnlp { template struct NegativeOrthant : ConstraintSetBase<_Scalar> { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = ConstraintSetBase; using ActiveType = typename Base::ActiveType; diff --git a/include/proxnlp/modelling/costs/quadratic-residual.hpp b/include/proxnlp/modelling/costs/quadratic-residual.hpp index e9675f57..ab9b069b 100644 --- a/include/proxnlp/modelling/costs/quadratic-residual.hpp +++ b/include/proxnlp/modelling/costs/quadratic-residual.hpp @@ -20,7 +20,7 @@ struct QuadraticResidualCostTpl : public CostFunctionBaseTpl<_Scalar> { public: using Scalar = _Scalar; using FunctionType = C2FunctionTpl; // base constraint func to use - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using RowMatrixXs = Eigen::Matrix; using Base = CostFunctionBaseTpl; using Base::computeGradient; @@ -74,6 +74,6 @@ struct QuadraticResidualCostTpl : public CostFunctionBaseTpl<_Scalar> { #include "proxnlp/modelling/costs/quadratic-residual.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/modelling/costs/quadratic-residual.txx" #endif diff --git a/include/proxnlp/modelling/costs/quadratic-residual.hxx b/include/proxnlp/modelling/costs/quadratic-residual.hxx index d64ae31a..5ca91983 100644 --- a/include/proxnlp/modelling/costs/quadratic-residual.hxx +++ b/include/proxnlp/modelling/costs/quadratic-residual.hxx @@ -23,12 +23,12 @@ template Scalar QuadraticResidualCostTpl::call(const ConstVectorRef &x) const { err = (*residual_)(x); - PROXNLP_NOMALLOC_BEGIN; + PROXSUITE_NLP_NOMALLOC_BEGIN; tmp_w_err.noalias() = weights_ * err; Scalar res = Scalar(0.5) * err.dot(tmp_w_err) + err.dot(slope_) + constant_; - PROXNLP_NOMALLOC_END; + PROXSUITE_NLP_NOMALLOC_END; return res; } diff --git a/include/proxnlp/modelling/costs/squared-distance.hpp b/include/proxnlp/modelling/costs/squared-distance.hpp index 4b91d867..56cd6af8 100644 --- a/include/proxnlp/modelling/costs/squared-distance.hpp +++ b/include/proxnlp/modelling/costs/squared-distance.hpp @@ -16,7 +16,7 @@ namespace proxnlp { template struct QuadraticDistanceCostTpl : QuadraticResidualCostTpl<_Scalar> { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using FunctionType = ManifoldDifferenceToPoint; using Manifold = ManifoldAbstractTpl; using Base = QuadraticResidualCostTpl; @@ -47,6 +47,6 @@ struct QuadraticDistanceCostTpl : QuadraticResidualCostTpl<_Scalar> { } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/modelling/costs/squared-distance.txx" #endif diff --git a/include/proxnlp/modelling/residuals/linear.hpp b/include/proxnlp/modelling/residuals/linear.hpp index ed9166ec..9f581530 100644 --- a/include/proxnlp/modelling/residuals/linear.hpp +++ b/include/proxnlp/modelling/residuals/linear.hpp @@ -11,7 +11,7 @@ namespace proxnlp { */ template struct LinearFunctionTpl : C2FunctionTpl<_Scalar> { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = C2FunctionTpl; using Base::computeJacobian; @@ -39,7 +39,7 @@ template struct LinearFunctionDifferenceToPoint : ComposeFunctionTpl<_Scalar> { using Scalar = _Scalar; using Base = ComposeFunctionTpl; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Manifold = ManifoldAbstractTpl; @@ -50,7 +50,7 @@ struct LinearFunctionDifferenceToPoint : ComposeFunctionTpl<_Scalar> { : Base(std::make_shared>(A, b), std::make_shared>(space, target)) { - PROXNLP_DIM_CHECK(target, space->nx()); + PROXSUITE_NLP_DIM_CHECK(target, space->nx()); } }; diff --git a/include/proxnlp/modelling/residuals/rigid-transform-point.hpp b/include/proxnlp/modelling/residuals/rigid-transform-point.hpp index 4a418d1c..f904971f 100644 --- a/include/proxnlp/modelling/residuals/rigid-transform-point.hpp +++ b/include/proxnlp/modelling/residuals/rigid-transform-point.hpp @@ -8,7 +8,7 @@ namespace proxnlp { template struct RigidTransformationPointActionTpl : C2FunctionTpl { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); // convenience for rigid-body transformations using SE3 = pin::SE3Tpl; using QuatConstMap = Eigen::Map; @@ -44,6 +44,6 @@ struct RigidTransformationPointActionTpl : C2FunctionTpl { } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/modelling/residuals/rigid-transform-point.hpp" #endif diff --git a/include/proxnlp/modelling/residuals/state-residual.hpp b/include/proxnlp/modelling/residuals/state-residual.hpp index 39485b04..fd319bed 100644 --- a/include/proxnlp/modelling/residuals/state-residual.hpp +++ b/include/proxnlp/modelling/residuals/state-residual.hpp @@ -17,7 +17,7 @@ template struct ManifoldDifferenceToPoint : C2FunctionTpl<_Scalar> { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Base = C2FunctionTpl; using Base::operator(); @@ -33,7 +33,7 @@ struct ManifoldDifferenceToPoint : C2FunctionTpl<_Scalar> { : Base(space->nx(), space->ndx(), space->ndx()), target_(target), space_(space) { if (!space->isNormalized(target_)) { - PROXNLP_RUNTIME_ERROR( + PROXSUITE_NLP_RUNTIME_ERROR( "Target parameter is not a valid element of the manifold."); } } diff --git a/include/proxnlp/modelling/spaces/cartesian-product.hpp b/include/proxnlp/modelling/spaces/cartesian-product.hpp index ec622922..996f0db9 100644 --- a/include/proxnlp/modelling/spaces/cartesian-product.hpp +++ b/include/proxnlp/modelling/spaces/cartesian-product.hpp @@ -17,7 +17,7 @@ struct CartesianProductTpl : ManifoldAbstractTpl<_Scalar> { using Scalar = _Scalar; using Base = ManifoldAbstractTpl; - PROXNLP_DEFINE_MANIFOLD_TYPES(Base) + PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(Base) private: std::vector> components; @@ -164,6 +164,6 @@ CartesianProductTpl operator*(const ManifoldPtr &left, // implementation details #include "proxnlp/modelling/spaces/cartesian-product.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/modelling/spaces/cartesian-product.txx" #endif diff --git a/include/proxnlp/modelling/spaces/cartesian-product.hxx b/include/proxnlp/modelling/spaces/cartesian-product.hxx index b3754f0c..21137156 100644 --- a/include/proxnlp/modelling/spaces/cartesian-product.hxx +++ b/include/proxnlp/modelling/spaces/cartesian-product.hxx @@ -41,7 +41,7 @@ bool CartesianProductTpl::isNormalized(const ConstVectorRef &x) const { template template std::vector CartesianProductTpl::split_impl(VectorType &x) const { - PROXNLP_DIM_CHECK(x, this->nx()); + PROXSUITE_NLP_DIM_CHECK(x, this->nx()); std::vector out; Eigen::Index c = 0; for (std::size_t i = 0; i < numComponents(); i++) { @@ -56,7 +56,7 @@ template template std::vector CartesianProductTpl::split_vector_impl(VectorType &v) const { - PROXNLP_DIM_CHECK(v, this->ndx()); + PROXSUITE_NLP_DIM_CHECK(v, this->ndx()); std::vector out; Eigen::Index c = 0; for (std::size_t i = 0; i < numComponents(); i++) { diff --git a/include/proxnlp/modelling/spaces/multibody.hpp b/include/proxnlp/modelling/spaces/multibody.hpp index df605069..00f6e51f 100644 --- a/include/proxnlp/modelling/spaces/multibody.hpp +++ b/include/proxnlp/modelling/spaces/multibody.hpp @@ -21,7 +21,7 @@ struct MultibodyConfiguration : public ManifoldAbstractTpl<_Scalar, _Options> { using Self = MultibodyConfiguration; using ModelType = pinocchio::ModelTpl; using Base = ManifoldAbstractTpl; - PROXNLP_DEFINE_MANIFOLD_TYPES(Base) + PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(Base) MultibodyConfiguration(const ModelType &model) : model_(model){}; @@ -119,6 +119,6 @@ struct MultibodyPhaseSpace } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "./multibody.txx" #endif diff --git a/include/proxnlp/modelling/spaces/pinocchio-groups.hpp b/include/proxnlp/modelling/spaces/pinocchio-groups.hpp index d8759b66..d4485194 100644 --- a/include/proxnlp/modelling/spaces/pinocchio-groups.hpp +++ b/include/proxnlp/modelling/spaces/pinocchio-groups.hpp @@ -22,7 +22,7 @@ struct PinocchioLieGroup using Scalar = typename LieGroup::Scalar; enum { Options = LieGroup::Options }; using Base = ManifoldAbstractTpl; - PROXNLP_DEFINE_MANIFOLD_TYPES(Base) + PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(Base) LieGroup lg_; PinocchioLieGroup() {} diff --git a/include/proxnlp/modelling/spaces/sphere.hpp b/include/proxnlp/modelling/spaces/sphere.hpp index e35130d5..c5950447 100644 --- a/include/proxnlp/modelling/spaces/sphere.hpp +++ b/include/proxnlp/modelling/spaces/sphere.hpp @@ -16,7 +16,7 @@ struct Sphere<3, _Scalar, _Options> using Scalar = _Scalar; enum { Options = _Options }; using Base = ManifoldAbstractTpl; - PROXNLP_DEFINE_MANIFOLD_TYPES(Base) + PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(Base) /** * Geodesics on the 3D sphere are given by the great circles. diff --git a/include/proxnlp/modelling/spaces/tangent-bundle.hpp b/include/proxnlp/modelling/spaces/tangent-bundle.hpp index 72e95814..7b7f8002 100644 --- a/include/proxnlp/modelling/spaces/tangent-bundle.hpp +++ b/include/proxnlp/modelling/spaces/tangent-bundle.hpp @@ -17,7 +17,7 @@ struct TangentBundleTpl : public ManifoldAbstractTpl { using Scalar = typename Base::Scalar; enum { Options = Base::Options }; - PROXNLP_DEFINE_MANIFOLD_TYPES(Base) + PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(Base) /// Constructor using base space instance. TangentBundleTpl(Base base) : base_(base){}; @@ -79,7 +79,7 @@ struct TangentBundleTpl : public ManifoldAbstractTpl { template typename Point::SegmentReturnType getBasePointWrite(const Point &x) const { - return PROXNLP_EIGEN_CONST_CAST(Point, x).head(base_.nx()); + return PROXSUITE_NLP_EIGEN_CONST_CAST(Point, x).head(base_.nx()); } template @@ -91,14 +91,14 @@ struct TangentBundleTpl : public ManifoldAbstractTpl { template typename Tangent::SegmentReturnType getTangentHeadWrite(const Tangent &v) const { - return PROXNLP_EIGEN_CONST_CAST(Tangent, v).head(base_.ndx()); + return PROXSUITE_NLP_EIGEN_CONST_CAST(Tangent, v).head(base_.ndx()); } template Eigen::Block getBaseJacobian(const Jac &J) const { - return PROXNLP_EIGEN_CONST_CAST(Jac, J).topLeftCorner(base_.ndx(), - base_.ndx()); + return PROXSUITE_NLP_EIGEN_CONST_CAST(Jac, J).topLeftCorner(base_.ndx(), + base_.ndx()); } }; diff --git a/include/proxnlp/modelling/spaces/vector-space.hpp b/include/proxnlp/modelling/spaces/vector-space.hpp index ccdc52da..dbd96739 100644 --- a/include/proxnlp/modelling/spaces/vector-space.hpp +++ b/include/proxnlp/modelling/spaces/vector-space.hpp @@ -12,7 +12,7 @@ struct VectorSpaceTpl : public ManifoldAbstractTpl<_Scalar, _Options> { using Scalar = _Scalar; enum { Dim = _Dim, Options = _Options }; using Base = ManifoldAbstractTpl; - PROXNLP_DEFINE_MANIFOLD_TYPES(Base) + PROXSUITE_NLP_DEFINE_MANIFOLD_TYPES(Base) int dim_; diff --git a/include/proxnlp/pdal.hpp b/include/proxnlp/pdal.hpp index 7d69dfee..839d2e0c 100644 --- a/include/proxnlp/pdal.hpp +++ b/include/proxnlp/pdal.hpp @@ -22,7 +22,7 @@ namespace proxnlp { template struct ALMeritFunctionTpl { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Problem = ProblemTpl; using Workspace = WorkspaceTpl; using ConstraintObject = ConstraintObjectTpl; @@ -45,6 +45,6 @@ template struct ALMeritFunctionTpl { #include "proxnlp/pdal.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/pdal.txx" #endif diff --git a/include/proxnlp/problem-base.hpp b/include/proxnlp/problem-base.hpp index fc352a16..30479da0 100644 --- a/include/proxnlp/problem-base.hpp +++ b/include/proxnlp/problem-base.hpp @@ -12,7 +12,7 @@ namespace proxnlp { template struct ProblemTpl { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); /// Generic constraint type using ConstraintObject = ConstraintObjectTpl; @@ -156,6 +156,6 @@ void allocateMultipliersOrResiduals( } // namespace proxnlp -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/problem-base.txx" #endif diff --git a/include/proxnlp/prox-solver.hpp b/include/proxnlp/prox-solver.hpp index 7ac0634d..78af75c9 100644 --- a/include/proxnlp/prox-solver.hpp +++ b/include/proxnlp/prox-solver.hpp @@ -38,7 +38,7 @@ enum KktSystem { KKT_CLASSIC, KKT_PRIMAL_DUAL }; template class ProxNLPSolverTpl { public: using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Problem = ProblemTpl; using Workspace = WorkspaceTpl; using Results = ResultsTpl; @@ -166,7 +166,7 @@ template class ProxNLPSolverTpl { void assembleKktMatrix(Workspace &workspace); /// Iterative refinement of the KKT linear system. - PROXNLP_INLINE bool iterativeRefinement(Workspace &workspace) const; + PROXSUITE_NLP_INLINE bool iterativeRefinement(Workspace &workspace) const; /// Update penalty parameter using the provided factor (with a safeguard /// ProxNLPSolverTpl::mu_lower). @@ -269,6 +269,6 @@ inline InertiaFlag checkInertia(const int ndx, const int nc, #include "proxnlp/prox-solver.hxx" -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/prox-solver.txx" #endif diff --git a/include/proxnlp/prox-solver.hxx b/include/proxnlp/prox-solver.hxx index 12e3bc1b..84234f10 100644 --- a/include/proxnlp/prox-solver.hxx +++ b/include/proxnlp/prox-solver.hxx @@ -34,8 +34,9 @@ ProxNLPSolverTpl::solve(const ConstVectorRef &x0, int nr = 0; const std::size_t numc = problem_->getNumConstraints(); if (numc != lams0.size()) { - PROXNLP_RUNTIME_ERROR("Specified number of constraints is not the same " - "as the provided number of multipliers!"); + PROXSUITE_NLP_RUNTIME_ERROR( + "Specified number of constraints is not the same " + "as the provided number of multipliers!"); } for (std::size_t i = 0; i < numc; i++) { nr = problem_->getConstraintDim(i); @@ -51,7 +52,7 @@ ConvergenceFlag ProxNLPSolverTpl::solve(const ConstVectorRef &x0, logger.active = false; if ((results_ == nullptr) || (workspace_ == nullptr)) { - PROXNLP_RUNTIME_ERROR( + PROXSUITE_NLP_RUNTIME_ERROR( "Either Results or Workspace are unitialized. Call setup() first."); } @@ -165,7 +166,7 @@ void ProxNLPSolverTpl::acceptMultipliers(Results &results, template void ProxNLPSolverTpl::computeMultipliers( const ConstVectorRef &inner_lams_data, Workspace &workspace) const { - PROXNLP_NOMALLOC_BEGIN; + PROXSUITE_NLP_NOMALLOC_BEGIN; workspace.data_shift_cstr_values = workspace.data_cstr_values + mu_ * workspace.data_lams_prev; // project multiplier estimate @@ -197,7 +198,7 @@ void ProxNLPSolverTpl::computeMultipliers( cstr_set.applyProjectionJacobian(workspace.shift_cstr_pdal[i], workspace.lams_pdal_reproj[i]); } - PROXNLP_NOMALLOC_END; + PROXSUITE_NLP_NOMALLOC_END; } template @@ -231,7 +232,7 @@ void ProxNLPSolverTpl::computeProblemDerivatives( template void ProxNLPSolverTpl::computePrimalResiduals(Workspace &workspace, Results &results) const { - PROXNLP_NOMALLOC_BEGIN; + PROXSUITE_NLP_NOMALLOC_BEGIN; workspace.data_shift_cstr_values = workspace.data_cstr_values + mu_ * results.data_lams_opt; @@ -245,7 +246,7 @@ void ProxNLPSolverTpl::computePrimalResiduals(Workspace &workspace, results.constraint_violations(long(i)) = math::infty_norm(cstr_prox_err); } results.prim_infeas = math::infty_norm(results.constraint_violations); - PROXNLP_NOMALLOC_END; + PROXSUITE_NLP_NOMALLOC_END; } template void ProxNLPSolverTpl::updatePenalty() { @@ -300,7 +301,7 @@ void ProxNLPSolverTpl::innerLoop(Workspace &workspace, prox_penalty.computeHessian(results.x_opt, workspace.prox_hess); } - PROXNLP_NOMALLOC_BEGIN; + PROXSUITE_NLP_NOMALLOC_BEGIN; //// fill in KKT RHS workspace.kkt_rhs.setZero(); workspace.kkt_rhs_corr.setZero(); @@ -328,8 +329,8 @@ void ProxNLPSolverTpl::innerLoop(Workspace &workspace, workspace.merit_gradient += workspace.prox_grad; } - PROXNLP_RAISE_IF_NAN_NAME(workspace.kkt_rhs, "kkt_rhs"); - PROXNLP_RAISE_IF_NAN_NAME(workspace.kkt_matrix, "kkt_matrix"); + PROXSUITE_NLP_RAISE_IF_NAN_NAME(workspace.kkt_rhs, "kkt_rhs"); + PROXSUITE_NLP_RAISE_IF_NAN_NAME(workspace.kkt_matrix, "kkt_matrix"); computePrimalResiduals(workspace, results); @@ -411,8 +412,8 @@ void ProxNLPSolverTpl::innerLoop(Workspace &workspace, iterativeRefinement(workspace); - PROXNLP_NOMALLOC_END; - PROXNLP_RAISE_IF_NAN_NAME(workspace.pd_step, "pd_step"); + PROXSUITE_NLP_NOMALLOC_END; + PROXSUITE_NLP_RAISE_IF_NAN_NAME(workspace.pd_step, "pd_step"); // Take the step @@ -429,19 +430,19 @@ void ProxNLPSolverTpl::innerLoop(Workspace &workspace, break; } default: - PROXNLP_RUNTIME_ERROR("Unrecognized linesearch alternative.\n"); + PROXSUITE_NLP_RUNTIME_ERROR("Unrecognized linesearch alternative.\n"); break; } tryStep(workspace, results, workspace.alpha_opt); - PROXNLP_RAISE_IF_NAN_NAME(workspace.alpha_opt, "alpha_opt"); - PROXNLP_RAISE_IF_NAN_NAME(workspace.x_trial, "x_trial"); - PROXNLP_RAISE_IF_NAN_NAME(workspace.data_lams_trial, "lams_trial"); + PROXSUITE_NLP_RAISE_IF_NAN_NAME(workspace.alpha_opt, "alpha_opt"); + PROXSUITE_NLP_RAISE_IF_NAN_NAME(workspace.x_trial, "x_trial"); + PROXSUITE_NLP_RAISE_IF_NAN_NAME(workspace.data_lams_trial, "lams_trial"); results.x_opt = workspace.x_trial; results.data_lams_opt = workspace.data_lams_trial; results.merit = phi_new; - PROXNLP_RAISE_IF_NAN_NAME(results.merit, "merit"); + PROXSUITE_NLP_RAISE_IF_NAN_NAME(results.merit, "merit"); invokeCallbacks(workspace, results); @@ -565,12 +566,12 @@ void ProxNLPSolverTpl::tolerancePostUpdate() noexcept { template void ProxNLPSolverTpl::tryStep(Workspace &workspace, const Results &results, Scalar alpha) { - PROXNLP_NOMALLOC_BEGIN; + PROXSUITE_NLP_NOMALLOC_BEGIN; workspace.tmp_dx_scaled = alpha * workspace.prim_step; manifold().integrate(results.x_opt, workspace.tmp_dx_scaled, workspace.x_trial); workspace.data_lams_trial = results.data_lams_opt + alpha * workspace.dual_step; - PROXNLP_NOMALLOC_END; + PROXSUITE_NLP_NOMALLOC_END; } } // namespace proxnlp diff --git a/include/proxnlp/results.hpp b/include/proxnlp/results.hpp index 72a73f87..513b9433 100644 --- a/include/proxnlp/results.hpp +++ b/include/proxnlp/results.hpp @@ -17,7 +17,7 @@ inline auto format_as(ConvergenceFlag fl) { return fmt::underlying(fl); } */ template struct ResultsTpl { using Scalar = _Scalar; - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Problem = ProblemTpl; using VecBool = Eigen::Matrix; @@ -83,6 +83,6 @@ template struct fmt::formatter<::proxnlp::ResultsTpl> : fmt::ostream_formatter { }; -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/results.txx" #endif diff --git a/include/proxnlp/workspace.hpp b/include/proxnlp/workspace.hpp index 781ead59..c0c40431 100644 --- a/include/proxnlp/workspace.hpp +++ b/include/proxnlp/workspace.hpp @@ -23,7 +23,7 @@ template struct WorkspaceTpl { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Problem = ProblemTpl; /// Newton iteration variables @@ -199,6 +199,6 @@ template struct fmt::formatter> : fmt::ostream_formatter { }; -#ifdef PROXNLP_ENABLE_TEMPLATE_INSTANTIATION +#ifdef PROXSUITE_NLP_ENABLE_TEMPLATE_INSTANTIATION #include "proxnlp/workspace.txx" #endif diff --git a/python/expose-cost.cpp b/python/expose-cost.cpp index 0f60997c..71ea47d5 100644 --- a/python/expose-cost.cpp +++ b/python/expose-cost.cpp @@ -19,7 +19,7 @@ using context::VectorRef; using context::VectorXs; struct CostWrapper : Cost, bp::wrapper { - PROXNLP_DYNAMIC_TYPEDEFS(Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); using Cost::Cost; diff --git a/python/expose-ldlt.cpp b/python/expose-ldlt.cpp index 988aaa8f..37ad6761 100644 --- a/python/expose-ldlt.cpp +++ b/python/expose-ldlt.cpp @@ -51,7 +51,7 @@ void exposeLdltRoutines() { .def(LDLTVisitor()) .def("print_sparsity", &BlockLDLT::print_sparsity, "self"_a, "Print the sparsity pattern of the matrix to factorize."); -#ifdef PROXNLP_ENABLE_PROXSUITE_LDLT +#ifdef PROXSUITE_NLP_USE_PROXSUITE_LDLT using ProxSuiteLDLT = linalg::ProxSuiteLDLTWrapper; bp::class_( "ProxSuiteLDLT", "Wrapper around ProxSuite's custom LDLT.", bp::no_init) diff --git a/python/expose-manifold.cpp b/python/expose-manifold.cpp index 1775ba6e..c3216d63 100644 --- a/python/expose-manifold.cpp +++ b/python/expose-manifold.cpp @@ -1,4 +1,4 @@ -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO #include #include "proxnlp/modelling/spaces/pinocchio-groups.hpp" #include "proxnlp/modelling/spaces/multibody.hpp" @@ -129,7 +129,7 @@ exposeTangentBundle(const char *name, const char *docstring, Init init) { void exposeCartesianProduct(); -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO /// Expose a Pinocchio Lie group with a specified name, docstring, /// and no-arg default constructor. template @@ -222,7 +222,7 @@ void exposeManifolds() { .def(bp::init(bp::args("self", "dim"))); exposeCartesianProduct(); -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO exposePinocchioSpaces(); #endif } diff --git a/python/expose-pinocchio-residuals.cpp b/python/expose-pinocchio-residuals.cpp index f4fcc4db..d107822a 100644 --- a/python/expose-pinocchio-residuals.cpp +++ b/python/expose-pinocchio-residuals.cpp @@ -1,4 +1,4 @@ -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO #include "proxnlp/python/residuals.hpp" #include "proxnlp/modelling/residuals/rigid-transform-point.hpp" diff --git a/python/function.hpp b/python/function.hpp index cdfd6906..4f30edd3 100644 --- a/python/function.hpp +++ b/python/function.hpp @@ -7,7 +7,7 @@ namespace python { struct FunctionWrap : context::Function, bp::wrapper { public: - PROXNLP_DYNAMIC_TYPEDEFS(context::Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(context::Scalar); using context::Function::BaseFunctionTpl; @@ -18,7 +18,7 @@ struct FunctionWrap : context::Function, bp::wrapper { }; struct C1FunctionWrap : context::C1Function, bp::wrapper { - PROXNLP_DYNAMIC_TYPEDEFS(context::Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(context::Scalar); using context::C1Function::C1FunctionTpl; @@ -34,7 +34,7 @@ struct C1FunctionWrap : context::C1Function, bp::wrapper { }; struct C2FunctionWrap : context::C2Function, bp::wrapper { - PROXNLP_DYNAMIC_TYPEDEFS(context::Scalar); + PROXSUITE_NLP_DYNAMIC_TYPEDEFS(context::Scalar); using context::C2Function::C2FunctionTpl; diff --git a/python/fwd.hpp b/python/fwd.hpp index 6e6bcadf..16346037 100644 --- a/python/fwd.hpp +++ b/python/fwd.hpp @@ -22,7 +22,7 @@ void exposeFunctionTypes(); void exposeManifolds(); /// Expose defined residuals for modelling void exposeResiduals(); -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO /// Expose residuals dependent on Pinocchio void exposePinocchioResiduals(); #endif diff --git a/python/module.cpp b/python/module.cpp index 955af368..c88e4921 100644 --- a/python/module.cpp +++ b/python/module.cpp @@ -39,7 +39,7 @@ BOOST_PYTHON_MODULE(MODULE_NAME) { eigenpy::enableEigenPySpecific(); bp::import("warnings"); -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO bp::import("pinocchio"); #endif @@ -52,7 +52,7 @@ BOOST_PYTHON_MODULE(MODULE_NAME) { { bp::scope res_cope = get_namespace("residuals"); exposeResiduals(); -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO exposePinocchioResiduals(); #endif } diff --git a/tests/cholesky-block-sparse-bench.cpp b/tests/cholesky-block-sparse-bench.cpp index 0da396d6..c13780d1 100644 --- a/tests/cholesky-block-sparse-bench.cpp +++ b/tests/cholesky-block-sparse-bench.cpp @@ -185,7 +185,7 @@ BENCHMARK_TEMPLATE(ldlt_solve, Eigen::BunchKaufman) BENCHMARK_TEMPLATE(ldlt_solve_in_place, BlockLDLT) ->Apply(default_arguments); -#ifdef PROXNLP_ENABLE_PROXSUITE_LDLT +#ifdef PROXSUITE_NLP_USE_PROXSUITE_LDLT BENCHMARK_TEMPLATE(ldlt_compute, ProxSuiteLDLTWrapper) ->Apply(default_arguments_compute); diff --git a/tests/cholesky-block-sparse.cpp b/tests/cholesky-block-sparse.cpp index 56779ab2..cf7f1d0a 100644 --- a/tests/cholesky-block-sparse.cpp +++ b/tests/cholesky-block-sparse.cpp @@ -198,7 +198,7 @@ BOOST_AUTO_TEST_CASE(block_structure_allocator) { linalg::print_sparsity_pattern(modified_structure); } -#ifdef PROXNLP_ENABLE_PROXSUITE_LDLT +#ifdef PROXSUITE_NLP_USE_PROXSUITE_LDLT BOOST_FIXTURE_TEST_CASE(test_proxsuite_ldlt, ldlt_test_fixture, *utf::tolerance(TOL)) { diff --git a/tests/constraints.cpp b/tests/constraints.cpp index f04996cf..01b240bf 100644 --- a/tests/constraints.cpp +++ b/tests/constraints.cpp @@ -16,7 +16,7 @@ using namespace proxnlp; const int N = 20; VectorSpaceTpl space(N); -PROXNLP_DYNAMIC_TYPEDEFS(double); +PROXSUITE_NLP_DYNAMIC_TYPEDEFS(double); BOOST_AUTO_TEST_CASE(test_equality) { VectorXs x0 = space.neutral(); diff --git a/tests/costs.cpp b/tests/costs.cpp index f9e066c6..04ed42b5 100644 --- a/tests/costs.cpp +++ b/tests/costs.cpp @@ -6,13 +6,13 @@ #include -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO #include "proxnlp/modelling/spaces/pinocchio-groups.hpp" #endif using namespace proxnlp; namespace utf = boost::unit_test; -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO namespace pin = pinocchio; using SE2 = PinocchioLieGroup>; #endif @@ -40,7 +40,7 @@ auto function_that_takes_a_cost(const CostPtr &) { BOOST_AUTO_TEST_SUITE(cost) -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO BOOST_AUTO_TEST_CASE(test_cost_sum, *utf::tolerance(1e-10)) { auto space = std::make_shared(); diff --git a/tests/finite-diff.cpp b/tests/finite-diff.cpp index 20dec87d..c406e7e4 100644 --- a/tests/finite-diff.cpp +++ b/tests/finite-diff.cpp @@ -1,5 +1,5 @@ #include "proxnlp/modelling/autodiff/finite-difference.hpp" -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO #include "proxnlp/modelling/spaces/pinocchio-groups.hpp" #endif #include "proxnlp/modelling/spaces/vector-space.hpp" @@ -13,7 +13,7 @@ BOOST_AUTO_TEST_SUITE(finite_diff) using namespace proxnlp; -PROXNLP_DYNAMIC_TYPEDEFS(double); +PROXSUITE_NLP_DYNAMIC_TYPEDEFS(double); static const double fd_eps = 1e-4; static const double prec = std::sqrt(fd_eps); @@ -72,7 +72,7 @@ BOOST_AUTO_TEST_CASE(test1) { fmt::print("Hessian:\n{}\n", H0); } -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO BOOST_AUTO_TEST_CASE(test2) { PinocchioLieGroup> space; diff --git a/tests/manifolds.cpp b/tests/manifolds.cpp index 6996fe80..a0222068 100644 --- a/tests/manifolds.cpp +++ b/tests/manifolds.cpp @@ -3,7 +3,7 @@ #include "proxnlp/modelling/spaces/vector-space.hpp" #include "proxnlp/modelling/spaces/cartesian-product.hpp" -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO #include #include "proxnlp/modelling/spaces/pinocchio-groups.hpp" #include "proxnlp/modelling/spaces/multibody.hpp" @@ -55,7 +55,7 @@ BOOST_AUTO_TEST_CASE(test_vectorspace) { x1 = prod2->rand(); } -#ifdef PROXNLP_WITH_PINOCCHIO +#ifdef PROXSUITE_NLP_WITH_PINOCCHIO BOOST_AUTO_TEST_CASE(test_lg_vecspace) { const int N = 4; diff --git a/tests/util.hpp b/tests/util.hpp index 7481651e..ce1111b1 100644 --- a/tests/util.hpp +++ b/tests/util.hpp @@ -9,7 +9,7 @@ using proxnlp::linalg::BlockKind; using proxnlp::linalg::isize; using proxnlp::linalg::SymbolicBlockMatrix; using Scalar = double; -PROXNLP_DYNAMIC_TYPEDEFS(Scalar); +PROXSUITE_NLP_DYNAMIC_TYPEDEFS(Scalar); } // namespace /// Sample for the GOE (Gaussian Orthogonal Ensemble) From 911ccc9070f46f49676da8492d7bbe7f570bf215 Mon Sep 17 00:00:00 2001 From: ManifoldFR Date: Mon, 18 Dec 2023 17:44:34 +0100 Subject: [PATCH 2/2] [examples] change references to proxnlp to proxsuite_nlp --- examples/l1_qp.py | 2 +- examples/solo_inverse_geom.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/l1_qp.py b/examples/l1_qp.py index a6d792bd..efce0e4d 100644 --- a/examples/l1_qp.py +++ b/examples/l1_qp.py @@ -1,5 +1,5 @@ """ -Solve an L1-penalized QP using PROXNLP. +Solve an L1-penalized QP using proxsuite_nlp. """ import proxsuite_nlp import numpy as np diff --git a/examples/solo_inverse_geom.py b/examples/solo_inverse_geom.py index e7b4ed1a..ba70fa46 100644 --- a/examples/solo_inverse_geom.py +++ b/examples/solo_inverse_geom.py @@ -1,6 +1,6 @@ """ Inverse kinematics with friction cone constraint. -We compare PROXNLP with the solver IPOPT. +We compare proxsuite_nlp with the solver IPOPT. min Dq, f || q - q0 ||**2 + || f ||**2 @@ -213,7 +213,7 @@ def compute_cost(q_ref, fs): viz.display(qopt_ipopt) -# Problem PROXNLP +# Problem proxsuite_nlp xspace = MultibodyPhaseSpace(model) pb_space = VectorSpace(4 * 3 + (xspace.ndx))