alpaqa 1.1.0a1
Nonconvex constrained optimization
Loading...
Searching...
No Matches
alpaqa Namespace Reference

Namespaces

namespace  anonymous_namespace{ocproblem-counters.cpp}
namespace  anonymous_namespace{problem-counters.cpp}
namespace  anonymous_namespace{qpalm-adapter.cpp}
namespace  casadi
namespace  casadi_loader
namespace  cutest
namespace  detail
namespace  dl
namespace  functions
namespace  lbfgsb
namespace  lbfgspp
namespace  params
namespace  sets
namespace  sparsity
namespace  util
namespace  vec_util

Classes

struct  ALMParams
 Parameters for the Augmented Lagrangian solver. More...
class  ALMSolver
 Augmented Lagrangian Method solver. More...
class  AndersonAccel
 Anderson Acceleration. More...
struct  AndersonAccelParams
 Parameters for the AndersonAccel class. More...
struct  AndersonDirection
struct  AndersonDirectionParams
 Parameters for the AndersonDirection class. More...
struct  Box
class  BoxConstrProblem
 Implements common problem functions for minimization problems with box constraints. More...
class  CasADiControlProblem
struct  CasADiFunctions
class  CasADiProblem
 Problem definition for a CasADi problem, loaded from a DLL. More...
struct  CBFGSParams
 Cautious BFGS update. More...
struct  ControlProblemVTable
struct  ControlProblemWithCounters
struct  ConvexNewtonDirection
struct  ConvexNewtonDirectionParams
 Parameters for the ConvexNewtonDirection class. More...
struct  ConvexNewtonRegularizationParams
 Parameters for the ConvexNewtonDirection class. More...
class  CUTEstLoader
class  CUTEstProblem
 Wrapper for CUTEst problems loaded from an external shared library. More...
struct  Dim
struct  EigenConfig
struct  EigenConfigd
 Double-precision double configuration. More...
struct  EigenConfigf
 Single-precision float configuration. More...
struct  EigenConfigl
 long double configuration. More...
struct  EvalCounter
struct  FISTAParams
 Tuning parameters for the FISTA algorithm. More...
struct  FISTAProgressInfo
class  FISTASolver
 FISTA solver for ALM. More...
struct  FISTAStats
class  FunctionalProblem
 Problem class that allows specifying the basic functions as C++ std::functions. More...
struct  InnerSolveOptions
struct  InnerStatsAccumulator
struct  InnerStatsAccumulator< FISTAStats< Conf > >
struct  InnerStatsAccumulator< lbfgsb::LBFGSBStats >
struct  InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > >
struct  InnerStatsAccumulator< PANOCOCPStats< Conf > >
struct  InnerStatsAccumulator< PANOCStats< Conf > >
struct  InnerStatsAccumulator< PANTRStats< Conf > >
struct  InnerStatsAccumulator< WolfeStats< Conf > >
struct  InnerStatsAccumulator< ZeroFPRStats< Conf > >
class  IpoptAdapter
 Based on https://coin-or.github.io/Ipopt/INTERFACES.html. More...
struct  is_config
struct  is_config< EigenConfigd >
struct  is_config< EigenConfigf >
struct  is_config< EigenConfigl >
struct  is_config< EigenConfigq >
struct  is_eigen_config
struct  is_eigen_config< EigenConfigd >
struct  is_eigen_config< EigenConfigf >
struct  is_eigen_config< EigenConfigl >
struct  is_eigen_config< EigenConfigq >
struct  KKTError
class  LBFGS
 Limited memory Broyden–Fletcher–Goldfarb–Shanno (L-BFGS) algorithm. More...
struct  LBFGSDirection
struct  LBFGSDirectionParams
 Parameters for the LBFGSDirection class. More...
struct  LBFGSParams
 Parameters for the LBFGS class. More...
struct  LBFGSStorage
 Layout: More...
class  LimitedMemoryQR
 Incremental QR factorization using modified Gram-Schmidt with reorthogonalization. More...
struct  LinConstrConverter
struct  LipschitzEstimateParams
 Parameters for the estimation of the Lipschitz constant of the gradient of the smooth term of the cost. More...
struct  NewtonTRDirection
struct  NewtonTRDirectionParams
 Parameters for the NewtonTRDirection class. More...
struct  NoopDirection
 Direction provider that provides no directions (apply always returns false). More...
struct  OCPDim
struct  OCPEvalCounter
struct  OCPEvaluator
struct  OCPVariables
struct  OwningQPALMData
struct  PANOCDirection
 This class outlines the interface for direction providers used by PANOC-like algorithms. More...
struct  PANOCOCPParams
 Tuning parameters for the PANOC algorithm. More...
struct  PANOCOCPProgressInfo
class  PANOCOCPSolver
struct  PANOCOCPStats
struct  PANOCParams
 Tuning parameters for the PANOC algorithm. More...
struct  PANOCProgressInfo
class  PANOCSolver
 PANOC solver for ALM. More...
struct  PANOCStats
struct  PANTRDirection
 This class outlines the interface for direction providers used by PANTR-like algorithms. More...
struct  PANTRParams
 Tuning parameters for the PANTR algorithm. More...
struct  PANTRProgressInfo
class  PANTRSolver
 PANTR solver for ALM. More...
struct  PANTRStats
struct  ProblemVTable
 Struct containing function pointers to all problem functions (like the objective and constraint functions, with their derivatives, and more). More...
struct  ProblemWithCounters
 Problem wrapper that keeps track of the number of evaluations and the run time of each function. More...
struct  prox_fn
 Proximal mapping customization point. More...
struct  prox_step_fn
 Proximal mapping customization point for forward-backward steps. More...
struct  ScopedMallocAllower
struct  ScopedMallocBlocker
struct  ScopedMallocChecker
struct  SerializedCasADiFunctions
struct  StatefulLQRFactor
struct  SteihaugCG
 Steihaug conjugate gradients procedure based on https://github.com/scipy/scipy/blob/583e70a50573169fc352b5dc6d94588a97c7389a/scipy/optimize/_trustregion_ncg.py#L44. More...
struct  SteihaugCGParams
 Parameters for SteihaugCG. More...
struct  StructuredLBFGSDirection
struct  StructuredLBFGSDirectionParams
 Parameters for the StructuredLBFGSDirection class. More...
struct  StructuredNewtonDirection
struct  StructuredNewtonDirectionParams
 Parameters for the StructuredNewtonDirection class. More...
struct  StructuredNewtonRegularizationParams
 Parameters for the StructuredNewtonDirection class. More...
class  TypeErasedControlProblem
 Nonlinear optimal control problem with finite horizon \( N \). More...
class  TypeErasedProblem
 The main polymorphic minimization problem interface. More...
class  UnconstrProblem
 Implements common problem functions for minimization problems without constraints. More...
struct  WolfeParams
 Tuning parameters for the unconstrained solver with Wolfe line search. More...
struct  WolfeProgressInfo
 Iterate information for the unconstrained solver with Wolfe line search. More...
class  WolfeSolver
 Unconstrained solver with Wolfe line search. More...
struct  WolfeStats
 Statistics for the unconstrained solver with Wolfe line search. More...
struct  ZeroFPRParams
 Tuning parameters for the ZeroFPR algorithm. More...
struct  ZeroFPRProgressInfo
class  ZeroFPRSolver
 ZeroFPR solver for ALM. More...
struct  ZeroFPRStats

Concepts

concept  Config
concept  VectorRefLike

Typedefs

using DefaultConfig = EigenConfigd
template<Config Conf = DefaultConfig>
using real_t = typename Conf::real_t
template<Config Conf = DefaultConfig>
using cplx_t = typename Conf::cplx_t
template<Config Conf = DefaultConfig>
using vec = typename Conf::vec
template<Config Conf = DefaultConfig>
using mvec = typename Conf::mvec
template<Config Conf = DefaultConfig>
using cmvec = typename Conf::cmvec
template<Config Conf = DefaultConfig>
using rvec = typename Conf::rvec
template<Config Conf = DefaultConfig>
using crvec = typename Conf::crvec
template<Config Conf = DefaultConfig>
using mat = typename Conf::mat
template<Config Conf = DefaultConfig>
using mmat = typename Conf::mmat
template<Config Conf = DefaultConfig>
using cmmat = typename Conf::cmmat
template<Config Conf = DefaultConfig>
using rmat = typename Conf::rmat
template<Config Conf = DefaultConfig>
using crmat = typename Conf::crmat
template<Config Conf = DefaultConfig>
using cmat = typename Conf::cmat
template<Config Conf = DefaultConfig>
using mcmat = typename Conf::mcmat
template<Config Conf = DefaultConfig>
using cmcmat = typename Conf::cmcmat
template<Config Conf = DefaultConfig>
using rcmat = typename Conf::rcmat
template<Config Conf = DefaultConfig>
using crcmat = typename Conf::crcmat
template<Config Conf = DefaultConfig>
using length_t = typename Conf::length_t
template<Config Conf = DefaultConfig>
using index_t = typename Conf::index_t
template<Config Conf = DefaultConfig>
using indexvec = typename Conf::indexvec
template<Config Conf = DefaultConfig>
using rindexvec = typename Conf::rindexvec
template<Config Conf = DefaultConfig>
using crindexvec = typename Conf::crindexvec
template<Config Conf = DefaultConfig>
using mindexvec = typename Conf::mindexvec
template<Config Conf = DefaultConfig>
using cmindexvec = typename Conf::cmindexvec
using casadi_int = long long int
using casadi_real = double
using function_dict_t = alpaqa_function_dict_t
using problem_register_t = alpaqa_problem_register_t
using control_problem_register_t = alpaqa_control_problem_register_t
using problem_functions_t = alpaqa_problem_functions_t
using control_problem_functions_t = alpaqa_control_problem_functions_t

Enumerations

enum class  LBFGSStepSize { BasedOnExternalStepSize = 0 , BasedOnCurvature = 1 , BasedOnGradientStepSize }
 Which method to use to select the L-BFGS step size. More...
enum class  PANOCStopCrit {
  ApproxKKT = 0 , ApproxKKT2 , ProjGradNorm , ProjGradNorm2 ,
  ProjGradUnitNorm , ProjGradUnitNorm2 , FPRNorm , FPRNorm2 ,
  Ipopt , LBFGSBpp
}
enum class  SolverStatus {
  Busy = 0 , Converged , MaxTime , MaxIter ,
  NotFinite , NoProgress , Interrupted , Exception
}
 Exit status of a numerical solver such as ALM or PANOC. More...

Functions

template<Config Conf = DefaultConfig>
void minimize_update_anderson (LimitedMemoryQR< Conf > &qr, rmat< Conf > G̃, crvec< Conf > rₖ, crvec< Conf > rₗₐₛₜ, crvec< Conf > gₖ, real_t< Conf > min_div_fac, rvec< Conf > γ_LS, rvec< Conf > xₖ_aa)
 Solve one step of Anderson acceleration to find a fixed point of a function g(x):
constexpr const char * enum_name (LBFGSStepSize s)
template<Config Conf, VectorRefLike< Conf > V>
constexpr auto const_or_mut_rvec (V &&v)
template<Config Conf>
InnerStatsAccumulator< FISTAStats< Conf > > & operator+= (InnerStatsAccumulator< FISTAStats< Conf > > &acc, const FISTAStats< Conf > &s)
constexpr const char * enum_name (PANOCStopCrit s)
std::ostream & operator<< (std::ostream &os, PANOCStopCrit s)
template<Config Conf>
InnerStatsAccumulator< PANOCOCPStats< Conf > > & operator+= (InnerStatsAccumulator< PANOCOCPStats< Conf > > &acc, const PANOCOCPStats< Conf > &s)
template<Config Conf>
InnerStatsAccumulator< PANOCStats< Conf > > & operator+= (InnerStatsAccumulator< PANOCStats< Conf > > &acc, const PANOCStats< Conf > &s)
template<Config Conf>
InnerStatsAccumulator< PANTRStats< Conf > > & operator+= (InnerStatsAccumulator< PANTRStats< Conf > > &acc, const PANTRStats< Conf > &s)
template<Config Conf>
InnerStatsAccumulator< WolfeStats< Conf > > & operator+= (InnerStatsAccumulator< WolfeStats< Conf > > &acc, const WolfeStats< Conf > &s)
template<Config Conf>
InnerStatsAccumulator< ZeroFPRStats< Conf > > & operator+= (InnerStatsAccumulator< ZeroFPRStats< Conf > > &acc, const ZeroFPRStats< Conf > &s)
template<Config Conf>
KKTError< Conf > compute_kkt_error (const TypeErasedProblem< Conf > &problem, crvec< Conf > x, crvec< Conf > y)
std::ostream & operator<< (std::ostream &, const OCPEvalCounter &)
OCPEvalCounter::OCPEvalTimeroperator+= (OCPEvalCounter::OCPEvalTimer &a, const OCPEvalCounter::OCPEvalTimer &b)
OCPEvalCounteroperator+= (OCPEvalCounter &a, const OCPEvalCounter &b)
OCPEvalCounter operator+ (OCPEvalCounter a, const OCPEvalCounter &b)
void check_finiteness (const auto &v, std::string_view msg)
 If the given vector v is not finite, break or throw an exception with the given message msg.
void check_finiteness (const std::floating_point auto &v, std::string_view msg)
template<class Problem>
auto ocproblem_with_counters (Problem &&p)
template<class Problem>
auto ocproblem_with_counters_ref (Problem &p)
std::ostream & operator<< (std::ostream &, const EvalCounter &)
EvalCounter::EvalTimeroperator+= (EvalCounter::EvalTimer &a, const EvalCounter::EvalTimer &b)
EvalCounteroperator+= (EvalCounter &a, const EvalCounter &b)
EvalCounter operator+ (EvalCounter a, const EvalCounter &b)
template<class Problem>
auto problem_with_counters (Problem &&p)
 Wraps the given problem into a ProblemWithCounters and keeps track of how many times each function is called, and how long these calls took.
template<class Problem>
auto problem_with_counters_ref (Problem &p)
 Wraps the given problem into a ProblemWithCounters and keeps track of how many times each function is called, and how long these calls took.
template<Config Conf>
void print_provided_functions (std::ostream &os, const TypeErasedProblem< Conf > &problem)
template<class Derived>
std::ostream & print_python (std::ostream &os, const Eigen::DenseBase< Derived > &M)
template<class Derived>
requires (Derived::ColsAtCompileTime == 1)
auto as_span (Eigen::DenseBase< Derived > &v)
 Convert an Eigen vector view to a std::span.
template<class Derived>
requires (Derived::ColsAtCompileTime == 1)
auto as_span (Eigen::DenseBase< Derived > &&v)
 Convert an Eigen vector view to a std::span.
template<class Derived>
requires (Derived::ColsAtCompileTime == 1)
auto as_span (const Eigen::DenseBase< Derived > &v)
 Convert an Eigen vector view to a std::span.
template<class T, size_t E>
auto as_vec (std::span< T, E > s)
 Convert a std::span to an Eigen::Vector view.
template<class Solver>
auto attach_cancellation (Solver &solver)
 Attach SIGINT and SIGTERM handlers to stop the given solver.
std::ostream & operator<< (std::ostream &os, SolverStatus s)
template<Config Conf>
Sparsity convert_csc (const auto &sp, sparsity::Symmetry symmetry)
template<class Func>
void register_function (function_dict_t *&extra_functions, std::string name, Func &&func)
 Make the given function available to alpaqa.
template<class Func>
void register_function (problem_register_t &result, std::string name, Func &&func)
template<class Func>
void register_function (control_problem_register_t &result, std::string name, Func &&func)
template<class Result, class T, class Ret, class... Args>
void register_member_function (Result &result, std::string name, Ret(T::*member)(Args...))
template<auto Member>
static auto member_caller ()
 Wrap the given member function or variable into a (possibly generic) lambda function that accepts the instance as a type-erased void pointer.
void unregister_functions (function_dict_t *&extra_functions)
 Cleans up the extra functions registered by register_function.
InnerStatsAccumulator< lbfgsb::LBFGSBStats > & operator+= (InnerStatsAccumulator< lbfgsb::LBFGSBStats > &acc, const lbfgsb::LBFGSBStats &s)
template<Config Conf>
InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > > & operator+= (InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > > &acc, const lbfgspp::LBFGSBStats< Conf > &s)
OwningQPALMData build_qpalm_problem (const TypeErasedProblem< EigenConfigd > &problem)

Variables

template<class T>
constexpr bool is_config_v = is_config<T>::value
template<class T>
constexpr bool is_eigen_config_v = is_eigen_config<T>::value
template<Config Conf>
constexpr const auto inf = std::numeric_limits<real_t<Conf>>::infinity()
template<Config Conf>
constexpr const auto NaN = std::numeric_limits<real_t<Conf>>::quiet_NaN()
template<Config Conf>
const rvec< Conf > null_vec = mvec<Conf>{nullptr, 0}
 Global empty vector for convenience.
template<Config Conf>
const rindexvec< Conf > null_indexvec = mindexvec<Conf>{nullptr, 0}
 Global empty index vector for convenience.
struct alpaqa::prox_fn prox
 Compute the proximal mapping.
struct alpaqa::prox_step_fn prox_step
 Compute a generalized forward-backward step.

Class Documentation

◆ alpaqa::FISTAProgressInfo

struct alpaqa::FISTAProgressInfo
Collaboration diagram for FISTAProgressInfo< Conf >:
Class Members
unsigned k
SolverStatus status
crvec x
crvec p
real_t norm_sq_p
crvec
crvec ŷ
real_t φγ
real_t ψ
crvec grad_ψ
real_t ψ_hat
crvec grad_ψ_hat
real_t L
real_t γ
real_t t
real_t ε
crvec Σ
crvec y
unsigned outer_iter
const TypeErasedProblem< config_t > * problem
const FISTAParams< config_t > * params

◆ alpaqa::FISTAStats

struct alpaqa::FISTAStats
Collaboration diagram for FISTAStats< Conf >:
Class Members
SolverStatus status = SolverStatus::Busy
real_t ε = inf<config_t>
nanoseconds elapsed_time {}
nanoseconds time_progress_callback {}
unsigned iterations = 0
unsigned stepsize_backtracks = 0
real_t final_γ = 0
real_t final_ψ = 0
real_t final_h = 0

◆ alpaqa::InnerSolveOptions

struct alpaqa::InnerSolveOptions
Collaboration diagram for InnerSolveOptions< Conf >:
Class Members
bool always_overwrite_results = true Return the final iterate and multipliers, even if the solver did not converge.
optional< nanoseconds > max_time = std::nullopt Maximum run time (in addition to the inner solver's own timeout).

Zero means no timeout.

real_t tolerance = 0 Desired tolerance (overrides the solver's own tolerance).

Zero means no tolerance (use solver's own tolerance).

ostream * os = nullptr Output stream to print to.
unsigned outer_iter = 0 The current iteration of the outer solver.
bool check = true Call check() before starting to solve.

◆ alpaqa::InnerStatsAccumulator

struct alpaqa::InnerStatsAccumulator
Collaboration diagram for InnerStatsAccumulator< InnerSolverStats >:

◆ alpaqa::InnerStatsAccumulator< FISTAStats< Conf > >

struct alpaqa::InnerStatsAccumulator< FISTAStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< FISTAStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner FISTA iterations.
unsigned stepsize_backtracks = 0 Total number of FISTA step size reductions.
real_t final_γ = 0 The final FISTA step size γ.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).
real_t final_h = 0 Final value of the nonsmooth cost \( h(\hat x) \).

◆ alpaqa::InnerStatsAccumulator< lbfgsb::LBFGSBStats >

struct alpaqa::InnerStatsAccumulator< lbfgsb::LBFGSBStats >
Collaboration diagram for InnerStatsAccumulator< lbfgsb::LBFGSBStats >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner PANOC iterations.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).
unsigned direction_update_rejected = 0 Total number of times that the L-BFGS update was rejected (i.e.

it could have resulted in a non-positive definite Hessian estimate).

◆ alpaqa::InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > >

struct alpaqa::InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
unsigned iterations = 0 Total number of inner PANOC iterations.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).

◆ alpaqa::InnerStatsAccumulator< PANOCOCPStats< Conf > >

struct alpaqa::InnerStatsAccumulator< PANOCOCPStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< PANOCOCPStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_prox {} Total time spent computing proximal mappings.
nanoseconds time_forward {} Total time spent doing forward simulations.
nanoseconds time_backward {} Total time spent doing backward gradient evaluations.
nanoseconds time_jacobians {} Total time spent computing dynamics Jacobians.
nanoseconds time_hessians {} Total time spent computing cost Hessians and Hessian-vector products.
nanoseconds time_indices {} Total time spent determining active indices.
nanoseconds time_lqr_factor {} Total time spent performing LQR factorizations.
nanoseconds time_lqr_solve {} Total time spent solving the (factorized) LQR problem.
nanoseconds time_lbfgs_indices {} Total time spent determining active indices for L-BFGS applications.
nanoseconds time_lbfgs_apply {} Total time spent applying L-BFGS estimates.
nanoseconds time_lbfgs_update {} Total time spent updating the L-BFGS estimate.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner PANOC iterations.
unsigned linesearch_failures = 0 Total number of PANOC line search failures.
unsigned linesearch_backtracks = 0 Total number of PANOC line search backtracking steps.
unsigned stepsize_backtracks = 0 Total number of PANOC step size reductions.
unsigned direction_failures = 0 Total number of times that the L-BFGS direction was not finite.
unsigned direction_update_rejected = 0 Total number of times that the L-BFGS update was rejected (i.e.

it could have resulted in a non-positive definite Hessian estimate).

unsigned τ_1_accepted = 0 Total number of times that a line search parameter of \( \tau = 1 \) was accepted (i.e.

no backtracking necessary).

unsigned count_τ = 0 The total number of line searches performed (used for computing the average value of \( \tau \)).
real_t sum_τ = 0 The sum of the line search parameter \( \tau \) in all iterations (used for computing the average value of \( \tau \)).
real_t final_γ = 0 The final PANOC step size γ.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).
real_t final_h = 0 Final value of the nonsmooth cost \( h(\hat x) \).
real_t final_φγ = 0 Final value of the forward-backward envelope, \( \varphi_\gamma(x) \) (note that this is in the point \( x \), not \( \hat x \)).

◆ alpaqa::InnerStatsAccumulator< PANOCStats< Conf > >

struct alpaqa::InnerStatsAccumulator< PANOCStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< PANOCStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner PANOC iterations.
unsigned linesearch_failures = 0 Total number of PANOC line search failures.
unsigned linesearch_backtracks = 0 Total number of PANOC line search backtracking steps.
unsigned stepsize_backtracks = 0 Total number of PANOC step size reductions.
unsigned direction_failures = 0 Total number of times that the L-BFGS direction was not finite.
unsigned direction_update_rejected = 0 Total number of times that the L-BFGS update was rejected (i.e.

it could have resulted in a non-positive definite Hessian estimate).

unsigned τ_1_accepted = 0 Total number of times that a line search parameter of \( \tau = 1 \) was accepted (i.e.

no backtracking necessary).

unsigned count_τ = 0 The total number of line searches performed (used for computing the average value of \( \tau \)).
real_t sum_τ = 0 The sum of the line search parameter \( \tau \) in all iterations (used for computing the average value of \( \tau \)).
real_t final_γ = 0 The final PANOC step size γ.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).
real_t final_h = 0 Final value of the nonsmooth cost \( h(\hat x) \).
real_t final_φγ = 0 Final value of the forward-backward envelope, \( \varphi_\gamma(x) \) (note that this is in the point \( x \), not \( \hat x \)).

◆ alpaqa::InnerStatsAccumulator< PANTRStats< Conf > >

struct alpaqa::InnerStatsAccumulator< PANTRStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< PANTRStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner PANTR iterations.
unsigned accelerated_step_rejected = 0 Total number of PANTR rejected accelerated steps.
unsigned stepsize_backtracks = 0 Total number of FB step size reductions.
unsigned direction_failures = 0 Total number of times that the accelerated direction was not finite.
unsigned direction_update_rejected = 0 Total number of times that the direction update was rejected (e.g.

it could have resulted in a non-positive definite Hessian estimate).

real_t final_γ = 0 The final FB step size γ.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).
real_t final_h = 0 Final value of the nonsmooth cost \( h(\hat x) \).
real_t final_φγ = 0 Final value of the forward-backward envelope, \( \varphi_\gamma(x) \) (note that this is in the point \( x \), not \( \hat x \)).

◆ alpaqa::InnerStatsAccumulator< WolfeStats< Conf > >

struct alpaqa::InnerStatsAccumulator< WolfeStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< WolfeStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner Wolfe iterations.
unsigned linesearch_failures = 0 Total number of Wolfe line search failures.
unsigned linesearch_backtracks = 0 Total number of Wolfe line search backtracking steps.
unsigned direction_failures = 0 Total number of times that the L-BFGS direction was not finite.
unsigned direction_update_rejected = 0 Total number of times that the L-BFGS update was rejected (i.e.

it could have resulted in a non-positive definite Hessian estimate).

unsigned τ_1_accepted = 0 Total number of times that a line search parameter of \( \tau = 1 \) was accepted (i.e.

no backtracking necessary).

unsigned count_τ = 0 The total number of line searches performed (used for computing the average value of \( \tau \)).
real_t sum_τ = 0 The sum of the line search parameter \( \tau \) in all iterations (used for computing the average value of \( \tau \)).
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).

◆ alpaqa::InnerStatsAccumulator< ZeroFPRStats< Conf > >

struct alpaqa::InnerStatsAccumulator< ZeroFPRStats< Conf > >
Collaboration diagram for InnerStatsAccumulator< ZeroFPRStats< Conf > >:
Class Members
nanoseconds elapsed_time {} Total elapsed time in the inner solver.
nanoseconds time_progress_callback {} Total time spent in the user-provided progress callback.
unsigned iterations = 0 Total number of inner ZeroFPR iterations.
unsigned linesearch_failures = 0 Total number of ZeroFPR line search failures.
unsigned linesearch_backtracks = 0 Total number of ZeroFPR line search backtracking steps.
unsigned stepsize_backtracks = 0 Total number of ZeroFPR step size reductions.
unsigned direction_failures = 0 Total number of times that the L-BFGS direction was not finite.
unsigned direction_update_rejected = 0 Total number of times that the L-BFGS update was rejected (i.e.

it could have resulted in a non-positive definite Hessian estimate).

unsigned τ_1_accepted = 0 Total number of times that a line search parameter of \( \tau = 1 \) was accepted (i.e.

no backtracking necessary).

unsigned count_τ = 0 The total number of line searches performed (used for computing the average value of \( \tau \)).
real_t sum_τ = 0 The sum of the line search parameter \( \tau \) in all iterations (used for computing the average value of \( \tau \)).
real_t final_γ = 0 The final ZeroFPR step size γ.
real_t final_ψ = 0 Final value of the smooth cost \( \psi(\hat x) \).
real_t final_h = 0 Final value of the nonsmooth cost \( h(\hat x) \).
real_t final_φγ = 0 Final value of the forward-backward envelope, \( \varphi_\gamma(x) \) (note that this is in the point \( x \), not \( \hat x \)).

◆ alpaqa::OCPDim

struct alpaqa::OCPDim
Collaboration diagram for OCPDim< Conf >:
Class Members
length_t N
length_t nx
length_t nu
length_t nh
length_t nc

◆ alpaqa::PANOCOCPStats

struct alpaqa::PANOCOCPStats
Collaboration diagram for PANOCOCPStats< Conf >:
Class Members
SolverStatus status = SolverStatus::Busy
real_t ε = inf<config_t>
nanoseconds elapsed_time {}
nanoseconds time_prox {}
nanoseconds time_forward {}
nanoseconds time_backward {}
nanoseconds time_jacobians {}
nanoseconds time_hessians {}
nanoseconds time_indices {}
nanoseconds time_lqr_factor {}
nanoseconds time_lqr_solve {}
nanoseconds time_lbfgs_indices {}
nanoseconds time_lbfgs_apply {}
nanoseconds time_lbfgs_update {}
nanoseconds time_progress_callback {}
unsigned iterations = 0
unsigned linesearch_failures = 0
unsigned linesearch_backtracks = 0
unsigned stepsize_backtracks = 0
unsigned direction_failures = 0
unsigned direction_update_rejected = 0
unsigned τ_1_accepted = 0
unsigned count_τ = 0
real_t sum_τ = 0
real_t final_γ = 0
real_t final_ψ = 0
real_t final_h = 0
real_t final_φγ = 0

◆ alpaqa::PANOCProgressInfo

struct alpaqa::PANOCProgressInfo
Collaboration diagram for PANOCProgressInfo< Conf >:
Class Members
unsigned k
SolverStatus status
crvec x
crvec p
real_t norm_sq_p
crvec
crvec ŷ
real_t φγ
real_t ψ
crvec grad_ψ
real_t ψ_hat
crvec grad_ψ_hat
crvec q
real_t L
real_t γ
real_t τ
real_t ε
crvec Σ
crvec y
unsigned outer_iter
const TypeErasedProblem< config_t > * problem
const PANOCParams< config_t > * params

◆ alpaqa::PANOCStats

struct alpaqa::PANOCStats
Collaboration diagram for PANOCStats< Conf >:
Class Members
SolverStatus status = SolverStatus::Busy
real_t ε = inf<config_t>
nanoseconds elapsed_time {}
nanoseconds time_progress_callback {}
unsigned iterations = 0
unsigned linesearch_failures = 0
unsigned linesearch_backtracks = 0
unsigned stepsize_backtracks = 0
unsigned direction_failures = 0
unsigned direction_update_rejected = 0
unsigned τ_1_accepted = 0
unsigned count_τ = 0
real_t sum_τ = 0
real_t final_γ = 0
real_t final_ψ = 0
real_t final_h = 0
real_t final_φγ = 0

◆ alpaqa::PANTRProgressInfo

struct alpaqa::PANTRProgressInfo
Collaboration diagram for PANTRProgressInfo< Conf >:
Class Members
unsigned k
SolverStatus status
crvec x
crvec p
real_t norm_sq_p
crvec
crvec ŷ
real_t φγ
real_t ψ
crvec grad_ψ
real_t ψ_hat
crvec grad_ψ_hat
crvec q
real_t L
real_t γ
real_t Δ
real_t ρ
real_t τ 1 if previous step accepted, 0 otherwise (PANOC compatibility)
real_t ε
crvec Σ
crvec y
unsigned outer_iter
const TypeErasedProblem< config_t > * problem
const PANTRParams< config_t > * params

◆ alpaqa::PANTRStats

struct alpaqa::PANTRStats
Collaboration diagram for PANTRStats< Conf >:
Class Members
SolverStatus status = SolverStatus::Busy
real_t ε = inf<config_t>
nanoseconds elapsed_time {}
nanoseconds time_progress_callback {}
unsigned iterations = 0
unsigned accelerated_step_rejected = 0
unsigned stepsize_backtracks = 0
unsigned direction_failures = 0
unsigned direction_update_rejected = 0
real_t final_γ = 0
real_t final_ψ = 0
real_t final_h = 0
real_t final_φγ = 0

◆ alpaqa::SerializedCasADiFunctions

struct alpaqa::SerializedCasADiFunctions
Collaboration diagram for SerializedCasADiFunctions:
Class Members
map< string, string > functions

◆ alpaqa::WolfeProgressInfo

struct alpaqa::WolfeProgressInfo
Collaboration diagram for WolfeProgressInfo< Conf >:
Class Members
unsigned k
SolverStatus status
crvec x
real_t ψ
crvec grad_ψ
crvec q
real_t τ
real_t ε
crvec Σ
crvec y
unsigned outer_iter
const TypeErasedProblem< config_t > * problem
const WolfeParams< config_t > * params

◆ alpaqa::WolfeStats

struct alpaqa::WolfeStats
Collaboration diagram for WolfeStats< Conf >:
Class Members
SolverStatus status = SolverStatus::Busy
real_t ε = inf<config_t>
nanoseconds elapsed_time {}
nanoseconds time_progress_callback {}
unsigned iterations = 0
unsigned linesearch_failures = 0
unsigned linesearch_backtracks = 0
unsigned direction_failures = 0
unsigned direction_update_rejected = 0
unsigned τ_1_accepted = 0
unsigned count_τ = 0
real_t sum_τ = 0
real_t final_ψ = 0

◆ alpaqa::ZeroFPRProgressInfo

struct alpaqa::ZeroFPRProgressInfo
Collaboration diagram for ZeroFPRProgressInfo< Conf >:
Class Members
unsigned k
SolverStatus status
crvec x
crvec p
real_t norm_sq_p
crvec
crvec ŷ
real_t φγ
real_t ψ
crvec grad_ψ
real_t ψ_hat
crvec grad_ψ_hat
crvec q
real_t L
real_t γ
real_t τ
real_t ε
crvec Σ
crvec y
unsigned outer_iter
const TypeErasedProblem< config_t > * problem
const ZeroFPRParams< config_t > * params

◆ alpaqa::ZeroFPRStats

struct alpaqa::ZeroFPRStats
Collaboration diagram for ZeroFPRStats< Conf >:
Class Members
SolverStatus status = SolverStatus::Busy
real_t ε = inf<config_t>
nanoseconds elapsed_time {}
nanoseconds time_progress_callback {}
unsigned iterations = 0
unsigned linesearch_failures = 0
unsigned linesearch_backtracks = 0
unsigned stepsize_backtracks = 0
unsigned direction_failures = 0
unsigned direction_update_rejected = 0
unsigned τ_1_accepted = 0
unsigned count_τ = 0
real_t sum_τ = 0
real_t final_γ = 0
real_t final_ψ = 0
real_t final_h = 0
real_t final_φγ = 0

Typedef Documentation

◆ DefaultConfig

◆ real_t

template<Config Conf = DefaultConfig>
using real_t = typename Conf::real_t

Definition at line 86 of file config.hpp.

◆ cplx_t

template<Config Conf = DefaultConfig>
using cplx_t = typename Conf::cplx_t

Definition at line 87 of file config.hpp.

◆ vec

template<Config Conf = DefaultConfig>
using vec = typename Conf::vec

Definition at line 88 of file config.hpp.

◆ mvec

template<Config Conf = DefaultConfig>
using mvec = typename Conf::mvec

Definition at line 89 of file config.hpp.

◆ cmvec

template<Config Conf = DefaultConfig>
using cmvec = typename Conf::cmvec

Definition at line 90 of file config.hpp.

◆ rvec

template<Config Conf = DefaultConfig>
using rvec = typename Conf::rvec

Definition at line 91 of file config.hpp.

◆ crvec

template<Config Conf = DefaultConfig>
using crvec = typename Conf::crvec

Definition at line 92 of file config.hpp.

◆ mat

template<Config Conf = DefaultConfig>
using mat = typename Conf::mat

Definition at line 93 of file config.hpp.

◆ mmat

template<Config Conf = DefaultConfig>
using mmat = typename Conf::mmat

Definition at line 94 of file config.hpp.

◆ cmmat

template<Config Conf = DefaultConfig>
using cmmat = typename Conf::cmmat

Definition at line 95 of file config.hpp.

◆ rmat

template<Config Conf = DefaultConfig>
using rmat = typename Conf::rmat

Definition at line 96 of file config.hpp.

◆ crmat

template<Config Conf = DefaultConfig>
using crmat = typename Conf::crmat

Definition at line 97 of file config.hpp.

◆ cmat

template<Config Conf = DefaultConfig>
using cmat = typename Conf::cmat

Definition at line 98 of file config.hpp.

◆ mcmat

template<Config Conf = DefaultConfig>
using mcmat = typename Conf::mcmat

Definition at line 99 of file config.hpp.

◆ cmcmat

template<Config Conf = DefaultConfig>
using cmcmat = typename Conf::cmcmat

Definition at line 100 of file config.hpp.

◆ rcmat

template<Config Conf = DefaultConfig>
using rcmat = typename Conf::rcmat

Definition at line 101 of file config.hpp.

◆ crcmat

template<Config Conf = DefaultConfig>
using crcmat = typename Conf::crcmat

Definition at line 102 of file config.hpp.

◆ length_t

template<Config Conf = DefaultConfig>
using length_t = typename Conf::length_t

Definition at line 103 of file config.hpp.

◆ index_t

template<Config Conf = DefaultConfig>
using index_t = typename Conf::index_t

Definition at line 104 of file config.hpp.

◆ indexvec

template<Config Conf = DefaultConfig>
using indexvec = typename Conf::indexvec

Definition at line 105 of file config.hpp.

◆ rindexvec

template<Config Conf = DefaultConfig>
using rindexvec = typename Conf::rindexvec

Definition at line 106 of file config.hpp.

◆ crindexvec

template<Config Conf = DefaultConfig>
using crindexvec = typename Conf::crindexvec

Definition at line 107 of file config.hpp.

◆ mindexvec

template<Config Conf = DefaultConfig>
using mindexvec = typename Conf::mindexvec

Definition at line 108 of file config.hpp.

◆ cmindexvec

template<Config Conf = DefaultConfig>
using cmindexvec = typename Conf::cmindexvec

Definition at line 109 of file config.hpp.

◆ casadi_int

using casadi_int = long long int

Definition at line 13 of file casadi-types.hpp.

◆ casadi_real

using casadi_real = double

Definition at line 16 of file casadi-types.hpp.

◆ function_dict_t

Definition at line 687 of file dl-problem.h.

◆ problem_register_t

Definition at line 688 of file dl-problem.h.

◆ control_problem_register_t

◆ problem_functions_t

Definition at line 690 of file dl-problem.h.

◆ control_problem_functions_t

Enumeration Type Documentation

◆ LBFGSStepSize

enum class LBFGSStepSize
strong

Which method to use to select the L-BFGS step size.

Enumerator
BasedOnExternalStepSize 

Initial inverse Hessian approximation is set to \( H_0 = \gamma I \), where \( \gamma \) is the forward-backward splitting step size.

BasedOnCurvature 

Initial inverse Hessian approximation is set to \( H_0 = \frac{s^\top y}{y^\top y} I \).

BasedOnGradientStepSize 

Definition at line 26 of file lbfgs.hpp.

◆ PANOCStopCrit

enum class PANOCStopCrit
strong
Enumerator
ApproxKKT 

Find an ε-approximate KKT point in the ∞-norm:

\[ \varepsilon = \left\| \gamma_k^{-1} (x^k - \hat x^k) + \nabla \psi(\hat x^k) - \nabla \psi(x^k) \right\|_\infty \]

ApproxKKT2 

Find an ε-approximate KKT point in the 2-norm:

\[ \varepsilon = \left\| \gamma_k^{-1} (x^k - \hat x^k) + \nabla \psi(\hat x^k) - \nabla \psi(x^k) \right\|_2 \]

ProjGradNorm 

∞-norm of the projected gradient with step size γ:

\[ \varepsilon = \left\| x^k - \Pi_C\left(x^k - \gamma_k \nabla \psi(x^k)\right) \right\|_\infty \]

ProjGradNorm2 

2-norm of the projected gradient with step size γ:

\[ \varepsilon = \left\| x^k - \Pi_C\left(x^k - \gamma_k \nabla \psi(x^k)\right) \right\|_2 \]

This is the same criterion as used by OpEn.

ProjGradUnitNorm 

∞-norm of the projected gradient with unit step size:

\[ \varepsilon = \left\| x^k - \Pi_C\left(x^k - \nabla \psi(x^k)\right) \right\|_\infty \]

ProjGradUnitNorm2 

2-norm of the projected gradient with unit step size:

\[ \varepsilon = \left\| x^k - \Pi_C\left(x^k - \nabla \psi(x^k)\right) \right\|_2 \]

FPRNorm 

∞-norm of fixed point residual:

\[ \varepsilon = \gamma_k^{-1} \left\| x^k - \Pi_C\left(x^k - \gamma_k \nabla \psi(x^k)\right) \right\|_\infty \]

FPRNorm2 

2-norm of fixed point residual:

\[ \varepsilon = \gamma_k^{-1} \left\| x^k - \Pi_C\left(x^k - \gamma_k \nabla \psi(x^k)\right) \right\|_2 \]

Ipopt 

The stopping criterion used by Ipopt, see https://link.springer.com/article/10.1007/s10107-004-0559-y equation (5).

Given a candidate iterate \( \hat x^k \) and the corresponding candidate Lagrange multipliers \( \hat y^k \) for the general constraints \( g(x)\in D \), the multipliers \( w \) for the box constraints \( x\in C \) (that are otherwise not computed explicitly) are given by

\[w^k = v^k - \Pi_C(v^k), \]

where

\[ \begin{aligned} v^k &\triangleq \hat x^k - \nabla f(\hat x^k) - \nabla g(\hat x^k)\, \hat y^k \\ &= \hat x^k - \nabla \psi(\hat x^k) \end{aligned} \]

The quantity that is compared to the (scaled) tolerance is then given by

\[ \begin{aligned} \varepsilon' &= \left\| \nabla f(\hat x^k) + \nabla g(\hat x^k)\, \hat y^k + w^k \right\|_\infty \\ &= \left\| \hat x^k - \Pi_C\left(v^k\right) \right\|_\infty \end{aligned} \]

Finally, the quantity is scaled by the factor

\[s_d \triangleq \max\left\{ s_\text{max},\;\frac{\|\hat y^k\|_1 + \|w^k\|_1}{2m + 2n} \right\} / s_\text{max}, \]

i.e. \( \varepsilon = \varepsilon' / s_d \).

LBFGSBpp 

The stopping criterion used by LBFGS++, see https://lbfgspp.statr.me/doc/classLBFGSpp_1_1LBFGSBParam.html#afb20e8fd6c6808c1f736218841ba6947.

\[ \varepsilon = \frac{\left\| x^k - \Pi_C\left(x^k - \nabla \psi(x^k)\right) \right\|_\infty} {\max\left\{1, \|x\|_2 \right\}} \]

Definition at line 8 of file panoc-stop-crit.hpp.

◆ SolverStatus

enum class SolverStatus
strong

Exit status of a numerical solver such as ALM or PANOC.

Enumerator
Busy 

In progress.

Converged 

Converged and reached given tolerance.

MaxTime 

Maximum allowed execution time exceeded.

MaxIter 

Maximum number of iterations exceeded.

NotFinite 

Intermediate results were infinite or not-a-number.

NoProgress 

No progress was made in the last iteration.

Interrupted 

Solver was interrupted by the user.

Exception 

An unexpected exception was thrown.

Definition at line 11 of file solverstatus.hpp.

Function Documentation

◆ minimize_update_anderson()

template<Config Conf = DefaultConfig>
void minimize_update_anderson ( LimitedMemoryQR< Conf > & qr,
rmat< Conf > ,
crvec< Conf > rₖ,
crvec< Conf > rₗₐₛₜ,
crvec< Conf > gₖ,
real_t< Conf > min_div_fac,
rvec< Conf > γ_LS,
rvec< Conf > xₖ_aa )
inline

Solve one step of Anderson acceleration to find a fixed point of a function g(x):

\( g(x^\star) - x^\star = 0 \)

Updates the QR factorization of \( \mathcal{R}_k = QR \), solves the least squares problem to find \( \gamma_\text{LS} \), computes the next iterate \( x_{k+1} \), and stores the current function value \( g_k \) in the matrix \( G \), which is used as a circular buffer.

\[ \begin{aligned} \def\gammaLS{\gamma_\text{LS}} m_k &= \min \{k, m\} \\ g_i &= g(x_i) \\ r_i &= r(x_i) g_i - x_i \\ \Delta r_i &= r_i - r_{i-1} \\ \mathcal{R}_k &= \begin{pmatrix} \Delta r_{k-m_k+1} & \dots & \Delta r_k \end{pmatrix} \in \R^{n\times m_k} \\ \gammaLS &= \argmin_{\gamma \in \R^{m_k}}\; \norm{\mathcal{R}_k \gamma - r_k}_2 \\ \alpha_i &= \begin{cases} \gammaLS[0] & i = 0 \\ \gammaLS[i] - \gammaLS[i-1] & 0 \lt i \lt m_k \\ 1 - \gammaLS[m_k - 1] & i = m_k \end{cases} \\ \tilde G_k &= \begin{pmatrix} g_{k - m_k} & \dots & g_{k-1} \end{pmatrix} \\ G_k &= \begin{pmatrix} g_{k - m_k} & \dots & g_{k} \end{pmatrix} \\ &= \begin{pmatrix} \tilde G_k & g_{k} \end{pmatrix} \\ x_{k+1} &= \sum_{i=0}^{m_k} \alpha_i\,g_{k - m_k + i} \\ &= G_k \alpha \\ \end{aligned} \]

Parameters
[in,out]qrQR factorization of \( \mathcal{R}_k \)
[in,out]Matrix of previous function values \( \tilde G_k \) (stored as ring buffer with the same indices as qr)
[in]rₖCurrent residual \( r_k \)
[in]rₗₐₛₜPrevious residual \( r_{k-1} \)
[in]gₖCurrent function value \( g_k \)
[in]min_div_facMinimum divisor when solving close to singular systems, scaled by the maximum eigenvalue of R
[out]γ_LSSolution to the least squares system
[out]xₖ_aaNext Anderson iterate

Definition at line 39 of file anderson-helpers.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ enum_name() [1/2]

const char * enum_name ( LBFGSStepSize s)
inlineconstexpr

Definition at line 229 of file lbfgs.hpp.

Here is the caller graph for this function:

◆ const_or_mut_rvec()

template<Config Conf, VectorRefLike< Conf > V>
auto const_or_mut_rvec ( V && v)
constexpr

Definition at line 15 of file ocp-vars.hpp.

Here is the caller graph for this function:

◆ operator+=() [1/12]

template<Config Conf>
InnerStatsAccumulator< FISTAStats< Conf > > & operator+= ( InnerStatsAccumulator< FISTAStats< Conf > > & acc,
const FISTAStats< Conf > & s )

Definition at line 189 of file fista.hpp.

◆ enum_name() [2/2]

const char * enum_name ( PANOCStopCrit s)
inlineconstexpr

Definition at line 105 of file panoc-stop-crit.hpp.

◆ operator<<() [1/4]

std::ostream & operator<< ( std::ostream & os,
PANOCStopCrit s )

Definition at line 7 of file panoc-stop-crit.cpp.

Here is the call graph for this function:

◆ operator+=() [2/12]

template<Config Conf>
InnerStatsAccumulator< PANOCOCPStats< Conf > > & operator+= ( InnerStatsAccumulator< PANOCOCPStats< Conf > > & acc,
const PANOCOCPStats< Conf > & s )

Definition at line 271 of file panoc-ocp.hpp.

◆ operator+=() [3/12]

template<Config Conf>
InnerStatsAccumulator< PANOCStats< Conf > > & operator+= ( InnerStatsAccumulator< PANOCStats< Conf > > & acc,
const PANOCStats< Conf > & s )

Definition at line 254 of file panoc.hpp.

◆ operator+=() [4/12]

template<Config Conf>
InnerStatsAccumulator< PANTRStats< Conf > > & operator+= ( InnerStatsAccumulator< PANTRStats< Conf > > & acc,
const PANTRStats< Conf > & s )

Definition at line 252 of file pantr.hpp.

◆ operator+=() [5/12]

template<Config Conf>
InnerStatsAccumulator< WolfeStats< Conf > > & operator+= ( InnerStatsAccumulator< WolfeStats< Conf > > & acc,
const WolfeStats< Conf > & s )

Definition at line 203 of file wolfe.hpp.

◆ operator+=() [6/12]

template<Config Conf>
InnerStatsAccumulator< ZeroFPRStats< Conf > > & operator+= ( InnerStatsAccumulator< ZeroFPRStats< Conf > > & acc,
const ZeroFPRStats< Conf > & s )

Definition at line 252 of file zerofpr.hpp.

◆ compute_kkt_error()

template<Config Conf>
KKTError< Conf > compute_kkt_error ( const TypeErasedProblem< Conf > & problem,
crvec< Conf > x,
crvec< Conf > y )

Definition at line 17 of file kkt-error.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator<<() [2/4]

std::ostream & operator<< ( std::ostream & os,
const OCPEvalCounter & c )

Definition at line 32 of file ocproblem-counters.cpp.

◆ operator+=() [7/12]

Definition at line 62 of file ocproblem-counters.hpp.

◆ operator+=() [8/12]

OCPEvalCounter & operator+= ( OCPEvalCounter & a,
const OCPEvalCounter & b )
inline

Definition at line 88 of file ocproblem-counters.hpp.

◆ operator+() [1/2]

OCPEvalCounter operator+ ( OCPEvalCounter a,
const OCPEvalCounter & b )
inline

Definition at line 114 of file ocproblem-counters.hpp.

◆ check_finiteness() [1/2]

void check_finiteness ( const auto & v,
std::string_view msg )
inline

If the given vector v is not finite, break or throw an exception with the given message msg.

Definition at line 510 of file ocproblem.hpp.

Here is the caller graph for this function:

◆ check_finiteness() [2/2]

void check_finiteness ( const std::floating_point auto & v,
std::string_view msg )
inline

Definition at line 518 of file ocproblem.hpp.

◆ ocproblem_with_counters()

template<class Problem>
auto ocproblem_with_counters ( Problem && p)
nodiscard

Definition at line 650 of file ocproblem.hpp.

◆ ocproblem_with_counters_ref()

template<class Problem>
auto ocproblem_with_counters_ref ( Problem & p)
nodiscard

Definition at line 657 of file ocproblem.hpp.

◆ operator<<() [3/4]

std::ostream & operator<< ( std::ostream & os,
const EvalCounter & c )

Definition at line 40 of file problem-counters.cpp.

◆ operator+=() [9/12]

EvalCounter::EvalTimer & operator+= ( EvalCounter::EvalTimer & a,
const EvalCounter::EvalTimer & b )
inline

Definition at line 62 of file problem-counters.hpp.

◆ operator+=() [10/12]

EvalCounter & operator+= ( EvalCounter & a,
const EvalCounter & b )
inline

Definition at line 89 of file problem-counters.hpp.

◆ operator+() [2/2]

EvalCounter operator+ ( EvalCounter a,
const EvalCounter & b )
inline

Definition at line 116 of file problem-counters.hpp.

◆ print_python()

template<class Derived>
std::ostream & print_python ( std::ostream & os,
const Eigen::DenseBase< Derived > & M )
Examples
C++/Advanced/lasso-fbs.cpp, and C++/CustomControlCppProblem/main.cpp.

Definition at line 13 of file print.hpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ as_span() [1/3]

template<class Derived>
requires (Derived::ColsAtCompileTime == 1)
auto as_span ( Eigen::DenseBase< Derived > & v)

Convert an Eigen vector view to a std::span.

Examples
problems/sparse-logistic-regression.cpp.

Definition at line 21 of file span.hpp.

Here is the caller graph for this function:

◆ as_span() [2/3]

template<class Derived>
requires (Derived::ColsAtCompileTime == 1)
auto as_span ( Eigen::DenseBase< Derived > && v)

Convert an Eigen vector view to a std::span.

Definition at line 30 of file span.hpp.

◆ as_span() [3/3]

template<class Derived>
requires (Derived::ColsAtCompileTime == 1)
auto as_span ( const Eigen::DenseBase< Derived > & v)

Convert an Eigen vector view to a std::span.

Definition at line 43 of file span.hpp.

◆ as_vec()

template<class T, size_t E>
auto as_vec ( std::span< T, E > s)

Convert a std::span to an Eigen::Vector view.

Definition at line 51 of file span.hpp.

Here is the caller graph for this function:

◆ attach_cancellation()

template<class Solver>
auto attach_cancellation ( Solver & solver)
nodiscard

Attach SIGINT and SIGTERM handlers to stop the given solver.

Parameters
solverThe solver that should be stopped by the handler.
Returns
A RAII object that detaches the handler when destroyed.

Definition at line 21 of file cancel.hpp.

Here is the caller graph for this function:

◆ operator<<() [4/4]

std::ostream & operator<< ( std::ostream & os,
SolverStatus s )

Definition at line 7 of file solverstatus.cpp.

Here is the call graph for this function:

◆ convert_csc()

template<Config Conf>
Sparsity convert_csc ( const auto & sp,
sparsity::Symmetry symmetry )

Definition at line 390 of file CasADiProblem.tpp.

Here is the caller graph for this function:

◆ register_function() [1/3]

template<class Func>
void register_function ( function_dict_t *& extra_functions,
std::string name,
Func && func )

Make the given function available to alpaqa.

See also
call_extra_func
call_extra_func

Definition at line 708 of file dl-problem.h.

Here is the caller graph for this function:

◆ register_function() [2/3]

template<class Func>
void register_function ( problem_register_t & result,
std::string name,
Func && func )

Definition at line 718 of file dl-problem.h.

Here is the call graph for this function:

◆ register_function() [3/3]

template<class Func>
void register_function ( control_problem_register_t & result,
std::string name,
Func && func )

Definition at line 725 of file dl-problem.h.

Here is the call graph for this function:

◆ register_member_function()

template<class Result, class T, class Ret, class... Args>
void register_member_function ( Result & result,
std::string name,
Ret(T::* member )(Args...) )

Definition at line 732 of file dl-problem.h.

Here is the call graph for this function:

◆ member_caller()

template<auto Member>
auto member_caller ( )
static

Wrap the given member function or variable into a (possibly generic) lambda function that accepts the instance as a type-erased void pointer.

The signature of the resulting function depends on the signature of the member function:

  • Ret Class::member(args...)Ret(void *self, args...)
  • Ret Class::member(args...) constRet(void *self, args...)
  • Ret Class::member(args...) constRet(const void *self, args...)

If the given member is a variable:

  • Type Class::memberType &(void *self)
  • Type Class::memberconst Type &(const void *self)
Examples
problems/sparse-logistic-regression.cpp.

Definition at line 802 of file dl-problem.h.

Here is the call graph for this function:

◆ unregister_functions()

void unregister_functions ( function_dict_t *& extra_functions)
inline

Cleans up the extra functions registered by register_function.

Note
This does not need to be called for the functions returned by the registration function, those functions will be cleaned up by alpaqa.
The alpaqa_problem_register_t and alpaqa_control_problem_register_t structs are part of the C API and do not automatically clean up their resources when destroyed, you have to do it manually by calling this function.

Definition at line 813 of file dl-problem.h.

◆ operator+=() [11/12]

Definition at line 136 of file lbfgsb-adapter.hpp.

◆ operator+=() [12/12]

template<Config Conf>
InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > > & operator+= ( InnerStatsAccumulator< lbfgspp::LBFGSBStats< Conf > > & acc,
const lbfgspp::LBFGSBStats< Conf > & s )

Definition at line 102 of file lbfgsb-adapter.hpp.

◆ build_qpalm_problem()

OwningQPALMData build_qpalm_problem ( const TypeErasedProblem< EigenConfigd > & problem)

Definition at line 29 of file qpalm-adapter.cpp.

Here is the call graph for this function:

Variable Documentation

◆ is_config_v

template<class T>
bool is_config_v = is_config<T>::value
inlineconstexpr

Definition at line 17 of file config.hpp.

◆ is_eigen_config_v

template<class T>
bool is_eigen_config_v = is_eigen_config<T>::value
inlineconstexpr

Definition at line 25 of file config.hpp.

◆ inf

template<Config Conf>
const auto inf = std::numeric_limits<real_t<Conf>>::infinity()
constexpr

◆ NaN

template<Config Conf>
const auto NaN = std::numeric_limits<real_t<Conf>>::quiet_NaN()
constexpr

Definition at line 114 of file config.hpp.

◆ null_vec

template<Config Conf>
const rvec<Conf> null_vec = mvec<Conf>{nullptr, 0}
inline

Global empty vector for convenience.

Definition at line 193 of file config.hpp.

◆ null_indexvec

template<Config Conf>
const rindexvec<Conf> null_indexvec = mindexvec<Conf>{nullptr, 0}
inline

Global empty index vector for convenience.

Definition at line 196 of file config.hpp.