aligator  0.16.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
merit-function.hpp
Go to the documentation of this file.
1
3#pragma once
4
5#include "aligator/fwd.hpp"
7
8namespace aligator {
9
10template <typename Scalar> class ConstraintProximalScalerTpl;
11
13template <typename Scalar>
15 const TrajOptDataTpl<Scalar> &prob_data);
16
49template <typename _Scalar> struct ALFunction {
50 using Scalar = _Scalar;
59
62 static Scalar evaluate(const Scalar mudyn, const Scalar mucstr,
63 const TrajOptProblem &problem, Workspace &workspace);
64
65 static Scalar directionalDerivative(const Scalar mudyn, const Scalar mucstr,
66 const TrajOptProblem &problem,
67 Workspace &workspace);
68};
69
70#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
71extern template struct ALFunction<context::Scalar>;
73 const WorkspaceTpl<context::Scalar> &workspace,
74 const TrajOptDataTpl<context::Scalar> &prob_data);
75#endif
76} // namespace aligator
Forward declarations.
Main package namespace.
Scalar costDirectionalDerivative(const WorkspaceTpl< Scalar > &workspace, const TrajOptDataTpl< Scalar > &prob_data)
Compute the directional derivative of the cost function.
Primal-dual augmented Lagrangian merit function.
StageDataTpl< Scalar > StageData
static Scalar directionalDerivative(const Scalar mudyn, const Scalar mucstr, const TrajOptProblem &problem, Workspace &workspace)
StageFunctionDataTpl< Scalar > StageFunctionData
TrajOptProblemTpl< Scalar > TrajOptProblem
WorkspaceTpl< Scalar > Workspace
TrajOptDataTpl< Scalar > TrajOptData
ConstraintStackTpl< Scalar > ConstraintStack
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
static Scalar evaluate(const Scalar mudyn, const Scalar mucstr, const TrajOptProblem &problem, Workspace &workspace)
Compute the merit function at the trial point.
StageModelTpl< Scalar > StageModel
Convenience class to manage a stack of constraints.
Data struct for stage models StageModelTpl.
Base struct for function data.
A stage in the control problem.
Problem data struct.
Trajectory optimization problem.
Workspace for solver SolverProxDDP.
Definition workspace.hpp:27