1+ /* *****************************************************************************
2+ Copyright (c) 2020, Farbod Farshidian. All rights reserved.
3+
4+ Redistribution and use in source and binary forms, with or without
5+ modification, are permitted provided that the following conditions are met:
6+
7+ * Redistributions of source code must retain the above copyright notice, this
8+ list of conditions and the following disclaimer.
9+
10+ * Redistributions in binary form must reproduce the above copyright notice,
11+ this list of conditions and the following disclaimer in the documentation
12+ and/or other materials provided with the distribution.
13+
14+ * Neither the name of the copyright holder nor the names of its
15+ contributors may be used to endorse or promote products derived from
16+ this software without specific prior written permission.
17+
18+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+ AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+ IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21+ DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22+ FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23+ DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24+ SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25+ CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26+ OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27+ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28+ ******************************************************************************/
29+
30+ #pragma once
31+
32+ #include < ocs2_core/Types.h>
33+ #include < ocs2_oc/oc_problem/OptimalControlProblem.h>
34+
35+ namespace ocs2 {
36+ namespace ipm {
37+
38+ /* *
39+ * Removes the Newton directions of slack and dual variables and the linearized inequality constraints are removed from the linear system
40+ * equations for the Newton step computation. These terms are considered in the quadratic approximation of the Lagrangian.
41+ *
42+ * @param[in] barrierParam : The barrier parameter of the interior point method.
43+ * @param[in] slack : The slack variable associated with the inequality constraints.
44+ * @param[in] dual : The dual variable associated with the inequality constraints.
45+ * @param[in] ineqConstraints : Linear approximation of the inequality constraints.
46+ * @param[in, out] lagrangian : Quadratic approximation of the Lagrangian.
47+ */
48+ void condenseIneqConstraints (scalar_t barrierParam, const vector_t & slack, const vector_t & dual,
49+ const VectorFunctionLinearApproximation& ineqConstraints, ScalarFunctionQuadraticApproximation& lagrangian);
50+
51+ /* *
52+ * Computes the SSE of the residual in the perturbed complementary slackness.
53+ *
54+ * @param[in] barrierParam : The barrier parameter of the interior point method.
55+ * @param[in] slack : The slack variable associated with the inequality constraints.
56+ * @param[in] dual : The dual variable associated with the inequality constraints.
57+ * @return SSE of the residual in the perturbed complementary slackness
58+ */
59+ inline scalar_t evaluateComplementarySlackness (scalar_t barrierParam, const vector_t & slack, const vector_t & dual) {
60+ return (slack.array () * dual.array () - barrierParam).matrix ().squaredNorm ();
61+ }
62+
63+ /* *
64+ * Retrieves the Newton directions of the slack variable associated with state-input inequality constraints.
65+ *
66+ * @param[in] stateInputIneqConstraints : State-input inequality constraints
67+ * @param[in] dx : Newton direction of the state
68+ * @param[in] du : Newton direction of the input
69+ * @param[in] barrierParam : The barrier parameter of the interior point method.
70+ * @param[in] slackStateInputIneq : The slack variable associated with the state-input inequality constraints.
71+ * @return Newton directions of the slack variable.
72+ */
73+ vector_t retrieveSlackDirection (const VectorFunctionLinearApproximation& stateInputIneqConstraints, const vector_t & dx, const vector_t & du,
74+ scalar_t barrierParam, const vector_t & slackStateInputIneq);
75+
76+ /* *
77+ * Retrieves the Newton directions of the slack variable associated with state-only inequality constraints.
78+ *
79+ * @param[in] stateIneqConstraints : State-only inequality constraints
80+ * @param[in] dx : Newton direction of the state
81+ * @param[in] barrierParam : The barrier parameter of the interior point method.
82+ * @param[in] slackStateIneq : The slack variable associated with the state-only inequality constraints.
83+ * @return Newton directions of the slack variable.
84+ */
85+ vector_t retrieveSlackDirection (const VectorFunctionLinearApproximation& stateIneqConstraints, const vector_t & dx, scalar_t barrierParam,
86+ const vector_t & slackStateIneq);
87+
88+ /* *
89+ * Retrieves the Newton directions of the dual variable.
90+ *
91+ * @param[in] barrierParam : The barrier parameter of the interior point method.
92+ * @param[in] slack : The slack variable associated with the inequality constraints.
93+ * @param[in] dual : The dual variable associated with the inequality constraints.
94+ * @param[in] slackDirection : The Newton direction of the slack variable.
95+ * @return Newton directions of the dual variable.
96+ */
97+ vector_t retrieveDualDirection (scalar_t barrierParam, const vector_t & slack, const vector_t & dual, const vector_t & slackDirection);
98+
99+ /* *
100+ * Computes the step size via fraction-to-boundary-rule, which is introduced in the IPOPT's implementaion paper,
101+ * "On the implementation of an interior-point filter line-search algorithm for large-scale nonlinear programming"
102+ * https://link.springer.com/article/10.1007/s10107-004-0559-y
103+ *
104+ * @param [in] v: A variable (slack or dual).
105+ * @param [in] dv: The serach direction of the variable (slack dirction or dual dirction).
106+ * @param [in] marginRate: Margin rate to avoid the slack or dual variables becoming too close to 0. Typical values are 0.95 or 0.995.
107+ */
108+ scalar_t fractionToBoundaryStepSize (const vector_t & v, const vector_t & dv, scalar_t marginRate = 0.995 );
109+
110+ } // namespace ipm
111+ } // namespace ocs2
0 commit comments