WPILibC++ 2025.0.0-alpha-1-24-g6478ba6
sleipnir Namespace Reference

Namespaces

namespace  detail
 

Classes

struct  EqualityConstraints
 A vector of equality constraints of the form cₑ(x) = 0. More...
 
class  function_ref
 An implementation of std::function_ref, a lightweight non-owning reference to a callable. More...
 
class  function_ref< R(Args...)>
 
class  Gradient
 This class calculates the gradient of a a variable with respect to a vector of variables. More...
 
class  Hessian
 This class calculates the Hessian of a variable with respect to a vector of variables. More...
 
struct  InequalityConstraints
 A vector of inequality constraints of the form cᵢ(x) ≥ 0. More...
 
class  IntrusiveSharedPtr
 A custom intrusive shared pointer implementation without thread synchronization overhead. More...
 
class  Jacobian
 This class calculates the Jacobian of a vector of variables with respect to a vector of variables. More...
 
struct  MultistartResult
 The result of a multistart solve. More...
 
class  OCPSolver
 This class allows the user to pose and solve a constrained optimal control problem (OCP) in a variety of ways. More...
 
class  OptimizationProblem
 This class allows the user to pose a constrained nonlinear optimization problem in natural mathematical notation and solve it. More...
 
class  PoolAllocator
 This class is an allocator for the pool resource. More...
 
class  PoolResource
 This class implements a pool memory resource. More...
 
class  Profiler
 Records the number of profiler measurements (start/stop pairs) and the average duration between each start and stop call. More...
 
struct  SolverConfig
 Solver configuration. More...
 
struct  SolverIterationInfo
 Solver iteration information exposed to a user callback. More...
 
struct  SolverStatus
 Return value of OptimizationProblem::Solve() containing the cost function and constraint types and solver's exit condition. More...
 
class  Variable
 An autodiff variable pointing to an expression node. More...
 
class  VariableBlock
 A submatrix of autodiff variables with reference semantics. More...
 
class  VariableMatrix
 A matrix of autodiff variables. More...
 

Concepts

concept  ScalarLike
 
concept  SleipnirMatrixLike
 
concept  EigenMatrixLike
 
concept  EigenSolver
 
concept  MatrixLike
 

Enumerations

enum class  ExpressionType : uint8_t {
  kNone , kConstant , kLinear , kQuadratic ,
  kNonlinear
}
 Expression type. More...
 
enum class  TranscriptionMethod : uint8_t { kDirectTranscription , kDirectCollocation , kSingleShooting }
 Enum describing an OCP transcription method. More...
 
enum class  DynamicsType : uint8_t { kExplicitODE , kDiscrete }
 Enum describing a type of system dynamics constraints. More...
 
enum class  TimestepMethod : uint8_t { kFixed , kVariable , kVariableSingle }
 Enum describing the type of system timestep. More...
 
enum class  SolverExitCondition : int8_t {
  kSuccess = 0 , kSolvedToAcceptableTolerance = 1 , kCallbackRequestedStop = 2 , kTooFewDOFs = -1 ,
  kLocallyInfeasible = -2 , kFeasibilityRestorationFailed = -3 , kNonfiniteInitialCostOrConstraints = -4 , kDivergingIterates = -5 ,
  kMaxIterationsExceeded = -6 , kTimeout = -7
}
 Solver exit condition. More...
 

Functions

SLEIPNIR_DLLEXPORT VariableMatrix CwiseReduce (const VariableMatrix &lhs, const VariableMatrix &rhs, function_ref< Variable(const Variable &, const Variable &)> binaryOp)
 Applies a coefficient-wise reduce operation to two matrices. More...
 
SLEIPNIR_DLLEXPORT VariableMatrix Block (std::initializer_list< std::initializer_list< VariableMatrix > > list)
 Assemble a VariableMatrix from a nested list of blocks. More...
 
SLEIPNIR_DLLEXPORT VariableMatrix Block (const std::vector< std::vector< VariableMatrix > > &list)
 Assemble a VariableMatrix from a nested list of blocks. More...
 
SLEIPNIR_DLLEXPORT VariableMatrix Solve (const VariableMatrix &A, const VariableMatrix &B)
 Solves the VariableMatrix equation AX = B for X. More...
 
SLEIPNIR_DLLEXPORT Variable abs (const Variable &x)
 std::abs() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable acos (const Variable &x)
 std::acos() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable asin (const Variable &x)
 std::asin() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable atan (const Variable &x)
 std::atan() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable atan2 (const Variable &y, const Variable &x)
 std::atan2() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable cos (const Variable &x)
 std::cos() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable cosh (const Variable &x)
 std::cosh() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable erf (const Variable &x)
 std::erf() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable exp (const Variable &x)
 std::exp() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable hypot (const Variable &x, const Variable &y)
 std::hypot() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable pow (const Variable &base, const Variable &power)
 std::pow() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable log (const Variable &x)
 std::log() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable log10 (const Variable &x)
 std::log10() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable sign (const Variable &x)
 sign() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable sin (const Variable &x)
 std::sin() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable sinh (const Variable &x)
 std::sinh() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable sqrt (const Variable &x)
 std::sqrt() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable tan (const Variable &x)
 std::tan() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable tanh (const Variable &x)
 std::tanh() for Variables. More...
 
SLEIPNIR_DLLEXPORT Variable hypot (const Variable &x, const Variable &y, const Variable &z)
 std::hypot() for Variables. More...
 
template<typename F , typename State , typename Input , typename Time >
State RK4 (F &&f, State x, Input u, Time t0, Time dt)
 Performs 4th order Runge-Kutta integration of dx/dt = f(t, x, u) for dt. More...
 
SLEIPNIR_DLLEXPORT PoolResourceGlobalPoolResource ()
 Returns a global pool memory resource. More...
 
template<typename T >
PoolAllocator< T > GlobalPoolAllocator ()
 Returns an allocator for a global pool memory resource. More...
 
template<typename T , typename... Args>
IntrusiveSharedPtr< T > MakeIntrusiveShared (Args &&... args)
 Constructs an object of type T and wraps it in an intrusive shared pointer using args as the parameter list for the constructor of T. More...
 
template<typename T , typename Alloc , typename... Args>
IntrusiveSharedPtr< T > AllocateIntrusiveShared (Alloc alloc, Args &&... args)
 Constructs an object of type T and wraps it in an intrusive shared pointer using alloc as the storage allocator of T and args as the parameter list for the constructor of T. More...
 
template<typename... T>
void print (fmt::format_string< T... > fmt, T &&... args)
 Wrapper around fmt::print() that squelches write failure exceptions. More...
 
template<typename... T>
void print (std::FILE *f, fmt::format_string< T... > fmt, T &&... args)
 Wrapper around fmt::print() that squelches write failure exceptions. More...
 
template<typename... T>
void println (fmt::format_string< T... > fmt, T &&... args)
 Wrapper around fmt::println() that squelches write failure exceptions. More...
 
template<typename... T>
void println (std::FILE *f, fmt::format_string< T... > fmt, T &&... args)
 Wrapper around fmt::println() that squelches write failure exceptions. More...
 
SLEIPNIR_DLLEXPORT void Spy (std::ostream &file, const Eigen::SparseMatrix< double > &mat)
 Write the sparsity pattern of a sparse matrix to a file. More...
 
SLEIPNIR_DLLEXPORT void Spy (std::string_view filename, const Eigen::SparseMatrix< double > &mat)
 Write the sparsity pattern of a sparse matrix to a file. More...
 
template<typename R , typename... Args>
constexpr void swap (function_ref< R(Args...)> &lhs, function_ref< R(Args...)> &rhs) noexcept
 Swaps the referred callables of lhs and rhs. More...
 
template<typename R , typename... Args>
 function_ref (R(*)(Args...)) -> function_ref< R(Args...)>
 
template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
wpi::SmallVector< VariableMakeConstraints (LHS &&lhs, RHS &&rhs)
 Make a list of constraints. More...
 
template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
EqualityConstraints operator== (LHS &&lhs, RHS &&rhs)
 Equality operator that returns an equality constraint for two Variables. More...
 
template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints operator< (LHS &&lhs, RHS &&rhs)
 Less-than comparison operator that returns an inequality constraint for two Variables. More...
 
template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints operator<= (LHS &&lhs, RHS &&rhs)
 Less-than-or-equal-to comparison operator that returns an inequality constraint for two Variables. More...
 
template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints operator> (LHS &&lhs, RHS &&rhs)
 Greater-than comparison operator that returns an inequality constraint for two Variables. More...
 
template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints operator>= (LHS &&lhs, RHS &&rhs)
 Greater-than-or-equal-to comparison operator that returns an inequality constraint for two Variables. More...
 
SLEIPNIR_DLLEXPORT constexpr std::string_view ToMessage (const SolverExitCondition &exitCondition)
 Returns user-readable message corresponding to the exit condition. More...
 
template<typename DecisionVariables >
MultistartResult< DecisionVariables > Multistart (function_ref< MultistartResult< DecisionVariables >(const DecisionVariables &initialGuess)> solve, std::span< const DecisionVariables > initialGuesses)
 Solves an optimization problem from different starting points in parallel, then returns the solution with the lowest cost. More...
 
SLEIPNIR_DLLEXPORT void InteriorPoint (std::span< Variable > decisionVariables, std::span< Variable > equalityConstraints, std::span< Variable > inequalityConstraints, Variable &f, function_ref< bool(const SolverIterationInfo &info)> callback, const SolverConfig &config, bool feasibilityRestoration, Eigen::VectorXd &x, Eigen::VectorXd &s, SolverStatus *status)
 Finds the optimal solution to a nonlinear program using the interior-point method. More...
 

Variables

class SLEIPNIR_DLLEXPORT Hessian
 
class SLEIPNIR_DLLEXPORT Jacobian
 

Enumeration Type Documentation

◆ DynamicsType

enum class sleipnir::DynamicsType : uint8_t
strong

Enum describing a type of system dynamics constraints.

Enumerator
kExplicitODE 

The dynamics are a function in the form dx/dt = f(t, x, u).

kDiscrete 

The dynamics are a function in the form xₖ₊₁ = f(t, xₖ, uₖ).

◆ ExpressionType

enum class sleipnir::ExpressionType : uint8_t
strong

Expression type.

Used for autodiff caching.

Enumerator
kNone 

There is no expression.

kConstant 

The expression is a constant.

kLinear 

The expression is composed of linear and lower-order operators.

kQuadratic 

The expression is composed of quadratic and lower-order operators.

kNonlinear 

The expression is composed of nonlinear and lower-order operators.

◆ SolverExitCondition

enum class sleipnir::SolverExitCondition : int8_t
strong

Solver exit condition.

Enumerator
kSuccess 

Solved the problem to the desired tolerance.

kSolvedToAcceptableTolerance 

Solved the problem to an acceptable tolerance, but not the desired one.

kCallbackRequestedStop 

The solver returned its solution so far after the user requested a stop.

kTooFewDOFs 

The solver determined the problem to be overconstrained and gave up.

kLocallyInfeasible 

The solver determined the problem to be locally infeasible and gave up.

kFeasibilityRestorationFailed 

The solver failed to reach the desired tolerance, and feasibility restoration failed to converge.

kNonfiniteInitialCostOrConstraints 

The solver encountered nonfinite initial cost or constraints and gave up.

kDivergingIterates 

The solver encountered diverging primal iterates xₖ and/or sₖ and gave up.

kMaxIterationsExceeded 

The solver returned its solution so far after exceeding the maximum number of iterations.

kTimeout 

The solver returned its solution so far after exceeding the maximum elapsed wall clock time.

◆ TimestepMethod

enum class sleipnir::TimestepMethod : uint8_t
strong

Enum describing the type of system timestep.

Enumerator
kFixed 

The timestep is a fixed constant.

kVariable 

The timesteps are allowed to vary as independent decision variables.

kVariableSingle 

The timesteps are equal length but allowed to vary as a single decision variable.

◆ TranscriptionMethod

enum class sleipnir::TranscriptionMethod : uint8_t
strong

Enum describing an OCP transcription method.

Enumerator
kDirectTranscription 

Each state is a decision variable constrained to the integrated dynamics of the previous state.

kDirectCollocation 

The trajectory is modeled as a series of cubic polynomials where the centerpoint slope is constrained.

kSingleShooting 

States depend explicitly as a function of all previous states and all previous inputs.

Function Documentation

◆ abs()

SLEIPNIR_DLLEXPORT Variable sleipnir::abs ( const Variable x)
inline

std::abs() for Variables.

Parameters
xThe argument.

◆ acos()

SLEIPNIR_DLLEXPORT Variable sleipnir::acos ( const Variable x)
inline

std::acos() for Variables.

Parameters
xThe argument.

◆ AllocateIntrusiveShared()

template<typename T , typename Alloc , typename... Args>
IntrusiveSharedPtr< T > sleipnir::AllocateIntrusiveShared ( Alloc  alloc,
Args &&...  args 
)

Constructs an object of type T and wraps it in an intrusive shared pointer using alloc as the storage allocator of T and args as the parameter list for the constructor of T.

Template Parameters
TType of object for intrusive shared pointer.
AllocType of allocator for T.
ArgsTypes of constructor arguments.
Parameters
allocThe allocator for T.
argsConstructor arguments for T.

◆ asin()

SLEIPNIR_DLLEXPORT Variable sleipnir::asin ( const Variable x)
inline

std::asin() for Variables.

Parameters
xThe argument.

◆ atan()

SLEIPNIR_DLLEXPORT Variable sleipnir::atan ( const Variable x)
inline

std::atan() for Variables.

Parameters
xThe argument.

◆ atan2()

SLEIPNIR_DLLEXPORT Variable sleipnir::atan2 ( const Variable y,
const Variable x 
)
inline

std::atan2() for Variables.

Parameters
yThe y argument.
xThe x argument.

◆ Block() [1/2]

SLEIPNIR_DLLEXPORT VariableMatrix sleipnir::Block ( const std::vector< std::vector< VariableMatrix > > &  list)
inline

Assemble a VariableMatrix from a nested list of blocks.

Each row's blocks must have the same height, and the assembled block rows must have the same width. For example, for the block matrix [[A, B], [C]] to be constructible, the number of rows in A and B must match, and the number of columns in [A, B] and [C] must match.

This overload is for Python bindings only.

Parameters
listThe nested list of blocks.

◆ Block() [2/2]

SLEIPNIR_DLLEXPORT VariableMatrix sleipnir::Block ( std::initializer_list< std::initializer_list< VariableMatrix > >  list)
inline

Assemble a VariableMatrix from a nested list of blocks.

Each row's blocks must have the same height, and the assembled block rows must have the same width. For example, for the block matrix [[A, B], [C]] to be constructible, the number of rows in A and B must match, and the number of columns in [A, B] and [C] must match.

Parameters
listThe nested list of blocks.

◆ cos()

SLEIPNIR_DLLEXPORT Variable sleipnir::cos ( const Variable x)
inline

std::cos() for Variables.

Parameters
xThe argument.

◆ cosh()

SLEIPNIR_DLLEXPORT Variable sleipnir::cosh ( const Variable x)
inline

std::cosh() for Variables.

Parameters
xThe argument.

◆ CwiseReduce()

SLEIPNIR_DLLEXPORT VariableMatrix sleipnir::CwiseReduce ( const VariableMatrix lhs,
const VariableMatrix rhs,
function_ref< Variable(const Variable &, const Variable &)>  binaryOp 
)
inline

Applies a coefficient-wise reduce operation to two matrices.

Parameters
lhsThe left-hand side of the binary operator.
rhsThe right-hand side of the binary operator.
binaryOpThe binary operator to use for the reduce operation.

◆ erf()

SLEIPNIR_DLLEXPORT Variable sleipnir::erf ( const Variable x)
inline

std::erf() for Variables.

Parameters
xThe argument.

◆ exp()

SLEIPNIR_DLLEXPORT Variable sleipnir::exp ( const Variable x)
inline

std::exp() for Variables.

Parameters
xThe argument.

◆ function_ref()

template<typename R , typename... Args>
sleipnir::function_ref ( R(*)(Args...)  ) -> function_ref< R(Args...)>

◆ GlobalPoolAllocator()

template<typename T >
PoolAllocator< T > sleipnir::GlobalPoolAllocator ( )

Returns an allocator for a global pool memory resource.

Template Parameters
TThe type of object in the pool.

◆ GlobalPoolResource()

SLEIPNIR_DLLEXPORT PoolResource & sleipnir::GlobalPoolResource ( )

Returns a global pool memory resource.

◆ hypot() [1/2]

SLEIPNIR_DLLEXPORT Variable sleipnir::hypot ( const Variable x,
const Variable y 
)
inline

std::hypot() for Variables.

Parameters
xThe x argument.
yThe y argument.

◆ hypot() [2/2]

SLEIPNIR_DLLEXPORT Variable sleipnir::hypot ( const Variable x,
const Variable y,
const Variable z 
)
inline

std::hypot() for Variables.

Parameters
xThe x argument.
yThe y argument.
zThe z argument.

◆ InteriorPoint()

SLEIPNIR_DLLEXPORT void sleipnir::InteriorPoint ( std::span< Variable decisionVariables,
std::span< Variable equalityConstraints,
std::span< Variable inequalityConstraints,
Variable f,
function_ref< bool(const SolverIterationInfo &info)>  callback,
const SolverConfig config,
bool  feasibilityRestoration,
Eigen::VectorXd &  x,
Eigen::VectorXd &  s,
SolverStatus status 
)

Finds the optimal solution to a nonlinear program using the interior-point method.

A nonlinear program has the form:

     min_x f(x)
subject to cₑ(x) = 0
           cᵢ(x) ≥ 0

where f(x) is the cost function, cₑ(x) are the equality constraints, and cᵢ(x) are the inequality constraints.

Parameters
[in]decisionVariablesThe list of decision variables.
[in]equalityConstraintsThe list of equality constraints.
[in]inequalityConstraintsThe list of inequality constraints.
[in]fThe cost function.
[in]callbackThe user callback.
[in]configConfiguration options for the solver.
[in]feasibilityRestorationWhether to use feasibility restoration instead of the normal algorithm.
[in,out]xThe initial guess and output location for the decision variables.
[in,out]sThe initial guess and output location for the inequality constraint slack variables.
[out]statusThe solver status.

◆ log()

SLEIPNIR_DLLEXPORT Variable sleipnir::log ( const Variable x)
inline

std::log() for Variables.

Parameters
xThe argument.

◆ log10()

SLEIPNIR_DLLEXPORT Variable sleipnir::log10 ( const Variable x)
inline

std::log10() for Variables.

Parameters
xThe argument.

◆ MakeConstraints()

template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
wpi::SmallVector< Variable > sleipnir::MakeConstraints ( LHS &&  lhs,
RHS &&  rhs 
)

Make a list of constraints.

The standard form for equality constraints is c(x) = 0, and the standard form for inequality constraints is c(x) ≥ 0. This function takes constraints of the form lhs = rhs or lhs ≥ rhs and converts them to lhs - rhs = 0 or lhs - rhs ≥ 0.

Parameters
lhsLeft-hand side.
rhsRight-hand side.

◆ MakeIntrusiveShared()

template<typename T , typename... Args>
IntrusiveSharedPtr< T > sleipnir::MakeIntrusiveShared ( Args &&...  args)

Constructs an object of type T and wraps it in an intrusive shared pointer using args as the parameter list for the constructor of T.

Template Parameters
TType of object for intrusive shared pointer.
ArgsTypes of constructor arguments.
Parameters
argsConstructor arguments for T.

◆ Multistart()

template<typename DecisionVariables >
MultistartResult< DecisionVariables > sleipnir::Multistart ( function_ref< MultistartResult< DecisionVariables >(const DecisionVariables &initialGuess)>  solve,
std::span< const DecisionVariables >  initialGuesses 
)

Solves an optimization problem from different starting points in parallel, then returns the solution with the lowest cost.

Each solve is performed on a separate thread. Solutions from successful solves are always preferred over solutions from unsuccessful solves, and cost (lower is better) is the tiebreaker between successful solves.

Template Parameters
DecisionVariablesThe type containing the decision variable initial guess.
Parameters
solveA user-provided function that takes a decision variable initial guess and returns a MultistartResult.
initialGuessesA list of decision variable initial guesses to try.

◆ operator<()

template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints sleipnir::operator< ( LHS &&  lhs,
RHS &&  rhs 
)

Less-than comparison operator that returns an inequality constraint for two Variables.

Parameters
lhsLeft-hand side.
rhsLeft-hand side.

◆ operator<=()

template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints sleipnir::operator<= ( LHS &&  lhs,
RHS &&  rhs 
)

Less-than-or-equal-to comparison operator that returns an inequality constraint for two Variables.

Parameters
lhsLeft-hand side.
rhsLeft-hand side.

◆ operator==()

template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
EqualityConstraints sleipnir::operator== ( LHS &&  lhs,
RHS &&  rhs 
)

Equality operator that returns an equality constraint for two Variables.

Parameters
lhsLeft-hand side.
rhsLeft-hand side.

◆ operator>()

template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints sleipnir::operator> ( LHS &&  lhs,
RHS &&  rhs 
)

Greater-than comparison operator that returns an inequality constraint for two Variables.

Parameters
lhsLeft-hand side.
rhsLeft-hand side.

◆ operator>=()

template<typename LHS , typename RHS >
requires (ScalarLike<std::decay_t<LHS>> || MatrixLike<std::decay_t<LHS>>) && (ScalarLike<std::decay_t<RHS>> || MatrixLike<std::decay_t<RHS>>) && (!std::same_as<std::decay_t<LHS>, double> || !std::same_as<std::decay_t<RHS>, double>)
InequalityConstraints sleipnir::operator>= ( LHS &&  lhs,
RHS &&  rhs 
)

Greater-than-or-equal-to comparison operator that returns an inequality constraint for two Variables.

Parameters
lhsLeft-hand side.
rhsLeft-hand side.

◆ pow()

SLEIPNIR_DLLEXPORT Variable sleipnir::pow ( const Variable base,
const Variable power 
)
inline

std::pow() for Variables.

Parameters
baseThe base.
powerThe power.

◆ print() [1/2]

template<typename... T>
void sleipnir::print ( fmt::format_string< T... >  fmt,
T &&...  args 
)
inline

Wrapper around fmt::print() that squelches write failure exceptions.

◆ print() [2/2]

template<typename... T>
void sleipnir::print ( std::FILE *  f,
fmt::format_string< T... >  fmt,
T &&...  args 
)
inline

Wrapper around fmt::print() that squelches write failure exceptions.

◆ println() [1/2]

template<typename... T>
void sleipnir::println ( fmt::format_string< T... >  fmt,
T &&...  args 
)
inline

Wrapper around fmt::println() that squelches write failure exceptions.

◆ println() [2/2]

template<typename... T>
void sleipnir::println ( std::FILE *  f,
fmt::format_string< T... >  fmt,
T &&...  args 
)
inline

Wrapper around fmt::println() that squelches write failure exceptions.

◆ RK4()

template<typename F , typename State , typename Input , typename Time >
State sleipnir::RK4 ( F &&  f,
State  x,
Input  u,
Time  t0,
Time  dt 
)

Performs 4th order Runge-Kutta integration of dx/dt = f(t, x, u) for dt.

Parameters
fThe function to integrate. It must take two arguments x and u.
xThe initial value of x.
uThe value u held constant over the integration period.
t0The initial time.
dtThe time over which to integrate.

◆ sign()

SLEIPNIR_DLLEXPORT Variable sleipnir::sign ( const Variable x)
inline

sign() for Variables.

Parameters
xThe argument.

◆ sin()

SLEIPNIR_DLLEXPORT Variable sleipnir::sin ( const Variable x)
inline

std::sin() for Variables.

Parameters
xThe argument.

◆ sinh()

SLEIPNIR_DLLEXPORT Variable sleipnir::sinh ( const Variable x)
inline

std::sinh() for Variables.

Parameters
xThe argument.

◆ Solve()

SLEIPNIR_DLLEXPORT VariableMatrix sleipnir::Solve ( const VariableMatrix A,
const VariableMatrix B 
)

Solves the VariableMatrix equation AX = B for X.

Parameters
AThe left-hand side.
BThe right-hand side.
Returns
The solution X.

◆ Spy() [1/2]

SLEIPNIR_DLLEXPORT void sleipnir::Spy ( std::ostream &  file,
const Eigen::SparseMatrix< double > &  mat 
)
inline

Write the sparsity pattern of a sparse matrix to a file.

Each character represents an element with '.' representing zero, '+' representing positive, and '-' representing negative. Here's an example for a 3x3 identity matrix.

"+.." ".+." "..+"

Parameters
[out]fileA file stream.
[in]matThe sparse matrix.

◆ Spy() [2/2]

SLEIPNIR_DLLEXPORT void sleipnir::Spy ( std::string_view  filename,
const Eigen::SparseMatrix< double > &  mat 
)
inline

Write the sparsity pattern of a sparse matrix to a file.

Each character represents an element with "." representing zero, "+" representing positive, and "-" representing negative. Here's an example for a 3x3 identity matrix.

"+.." ".+." "..+"

Parameters
[in]filenameThe filename.
[in]matThe sparse matrix.

◆ sqrt()

SLEIPNIR_DLLEXPORT Variable sleipnir::sqrt ( const Variable x)
inline

std::sqrt() for Variables.

Parameters
xThe argument.

◆ swap()

template<typename R , typename... Args>
constexpr void sleipnir::swap ( function_ref< R(Args...)> &  lhs,
function_ref< R(Args...)> &  rhs 
)
constexprnoexcept

Swaps the referred callables of lhs and rhs.

◆ tan()

SLEIPNIR_DLLEXPORT Variable sleipnir::tan ( const Variable x)
inline

std::tan() for Variables.

Parameters
xThe argument.

◆ tanh()

SLEIPNIR_DLLEXPORT Variable sleipnir::tanh ( const Variable x)
inline

std::tanh() for Variables.

Parameters
xThe argument.

◆ ToMessage()

SLEIPNIR_DLLEXPORT constexpr std::string_view sleipnir::ToMessage ( const SolverExitCondition exitCondition)
constexpr

Returns user-readable message corresponding to the exit condition.

Parameters
exitConditionSolver exit condition.

Variable Documentation

◆ Hessian

◆ Jacobian