@@ -35,6 +35,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35
35
#include < ocs2_core/thread_support/ThreadPool.h>
36
36
37
37
#include < ocs2_oc/multiple_shooting/ProjectionMultiplierCoefficients.h>
38
+ #include < ocs2_oc/multiple_shooting/Transcription.h>
38
39
#include < ocs2_oc/oc_data/TimeDiscretization.h>
39
40
#include < ocs2_oc/oc_problem/OptimalControlProblem.h>
40
41
#include < ocs2_oc/oc_solver/SolverBase.h>
@@ -66,6 +67,8 @@ class IpmSolver : public SolverBase {
66
67
67
68
void getPrimalSolution (scalar_t finalTime, PrimalSolution* primalSolutionPtr) const override { *primalSolutionPtr = primalSolution_; }
68
69
70
+ const DualSolution* getDualSolution () const override { return &dualIneqTrajectory_; }
71
+
69
72
const ProblemMetrics& getSolutionMetrics () const override { return problemMetrics_; }
70
73
71
74
size_t getNumIterations () const override { return totalNumIterations_; }
@@ -84,9 +87,7 @@ class IpmSolver : public SolverBase {
84
87
85
88
vector_t getStateInputEqualityConstraintLagrangian (scalar_t time, const vector_t & state) const override ;
86
89
87
- MultiplierCollection getIntermediateDualSolution (scalar_t time) const override {
88
- throw std::runtime_error (" [IpmSolver] getIntermediateDualSolution() not available yet." );
89
- }
90
+ MultiplierCollection getIntermediateDualSolution (scalar_t time) const override ;
90
91
91
92
private:
92
93
void runImpl (scalar_t initTime, const vector_t & initState, scalar_t finalTime) override ;
@@ -123,12 +124,17 @@ class IpmSolver : public SolverBase {
123
124
void initializeProjectionMultiplierTrajectory (const std::vector<AnnotatedTime>& timeDiscretization,
124
125
vector_array_t & projectionMultiplierTrajectory) const ;
125
126
127
+ /* * Initializes for the slack and dual trajectories of the hard inequality constraints */
128
+ void initializeSlackDualTrajectory (const std::vector<AnnotatedTime>& timeDiscretization, const vector_array_t & x, const vector_array_t & u,
129
+ scalar_t barrierParam, vector_array_t & slackStateIneq, vector_array_t & dualStateIneq,
130
+ vector_array_t & slackStateInputIneq, vector_array_t & dualStateInputIneq);
131
+
126
132
/* * Creates QP around t, x(t), u(t). Returns performance metrics at the current {t, x(t), u(t)} */
127
133
PerformanceIndex setupQuadraticSubproblem (const std::vector<AnnotatedTime>& time, const vector_t & initState, const vector_array_t & x,
128
134
const vector_array_t & u, const vector_array_t & lmd, const vector_array_t & nu,
129
- scalar_t barrierParam, vector_array_t & slackStateIneq, vector_array_t & slackStateInputIneq ,
130
- vector_array_t & dualStateIneq, vector_array_t & dualStateInputIneq ,
131
- bool initializeSlackAndDualVariables , std::vector<Metrics>& metrics);
135
+ scalar_t barrierParam, const vector_array_t & slackStateIneq ,
136
+ const vector_array_t & slackStateInputIneq, const vector_array_t & dualStateIneq ,
137
+ const vector_array_t & dualStateInputIneq , std::vector<Metrics>& metrics);
132
138
133
139
/* * Computes only the performance metrics at the current {t, x(t), u(t)} */
134
140
PerformanceIndex computePerformance (const std::vector<AnnotatedTime>& time, const vector_t & initState, const vector_array_t & x,
@@ -142,15 +148,15 @@ class IpmSolver : public SolverBase {
142
148
vector_array_t deltaLmdSol; // delta_lmd(t)
143
149
vector_array_t deltaNuSol; // delta_nu(t)
144
150
vector_array_t deltaSlackStateIneq;
145
- vector_array_t deltaSlackStateInputIneq;
146
151
vector_array_t deltaDualStateIneq;
152
+ vector_array_t deltaSlackStateInputIneq;
147
153
vector_array_t deltaDualStateInputIneq;
148
154
scalar_t armijoDescentMetric; // inner product of the cost gradient and decision variable step
149
155
scalar_t maxPrimalStepSize;
150
156
scalar_t maxDualStepSize;
151
157
};
152
158
OcpSubproblemSolution getOCPSolution (const vector_t & delta_x0, scalar_t barrierParam, const vector_array_t & slackStateIneq,
153
- const vector_array_t & slackStateInputIneq , const vector_array_t & dualStateIneq ,
159
+ const vector_array_t & dualStateIneq , const vector_array_t & slackStateInputIneq ,
154
160
const vector_array_t & dualStateInputIneq);
155
161
156
162
/* * Extract the value function based on the last solved QP */
@@ -196,10 +202,8 @@ class IpmSolver : public SolverBase {
196
202
PrimalSolution primalSolution_;
197
203
vector_array_t costateTrajectory_;
198
204
vector_array_t projectionMultiplierTrajectory_;
199
- vector_array_t slackStateIneqTrajectory_;
200
- vector_array_t dualStateIneqTrajectory_;
201
- vector_array_t slackStateInputIneqTrajectory_;
202
- vector_array_t dualStateInputIneqTrajectory_;
205
+ DualSolution slackIneqTrajectory_;
206
+ DualSolution dualIneqTrajectory_;
203
207
204
208
// Value function in absolute state coordinates (without the constant value)
205
209
std::vector<ScalarFunctionQuadraticApproximation> valueFunction_;
@@ -212,6 +216,9 @@ class IpmSolver : public SolverBase {
212
216
std::vector<VectorFunctionLinearApproximation> stateInputIneqConstraints_;
213
217
std::vector<VectorFunctionLinearApproximation> constraintsProjection_;
214
218
219
+ // Constraint terms size
220
+ std::vector<multiple_shooting::ConstraintsSize> constraintsSize_;
221
+
215
222
// Lagrange multipliers
216
223
std::vector<multiple_shooting::ProjectionMultiplierCoefficients> projectionMultiplierCoefficients_;
217
224
0 commit comments