Skip to content

Commit d32d4e8

Browse files
mayatakafarbod-farshidian
authored andcommitted
Merged in feature/interior_point/trajectory_adjustment (pull request #687)
Feature/interior point/trajectory adjustment Approved-by: Farbod Farshidian
2 parents 3fba74e + c2ce839 commit d32d4e8

File tree

16 files changed

+484
-85
lines changed

16 files changed

+484
-85
lines changed

ocs2_doc/docs/intro.rst

+4-3
Original file line numberDiff line numberDiff line change
@@ -7,10 +7,11 @@ Introduction
77
**S**\ witched **S**\ ystems (OCS2). The toolbox provides an efficient
88
implementation of the following algorithms:
99

10-
* **SLQ**\: Continuous-time domain DDP
11-
* **iLQR**\: Discrete-time domain DDP
10+
* **SLQ**\: Continuous-time domain constrained DDP
11+
* **iLQR**\: Discrete-time domain constrained DDP
1212
* **SQP**\: Multiple-shooting algorithm based on `HPIPM <href="https://github.com/giaf/hpipm"/>`__
13-
* **PISOC**\: Path integral stochastic optimal control
13+
* **IPM**\: Multiple-shooting algorithm based on nonlinear interior point method
14+
* **SLP**\: Sequential Linear Programming based on `PIPG <href="https://arxiv.org/abs/2009.06980"/>`__
1415

1516
OCS2 handles general path constraints through Augmented Lagrangian or
1617
relaxed barrier methods. To facilitate the application of OCS2 in robotic

ocs2_doc/docs/overview.rst

+31-9
Original file line numberDiff line numberDiff line change
@@ -9,10 +9,11 @@ Overview
99
for **S**\ witched **S**\ ystems (OCS2). The toolbox provides an
1010
efficient implementation of the following algorithms:
1111

12-
* **SLQ**\: Continuous-time domain DDP
13-
* **iLQR**\: Discrete-time domain DDP
12+
* **SLQ**\: Continuous-time domain constrained DDP
13+
* **iLQR**\: Discrete-time domain constrained DDP
1414
* **SQP**\: Multiple-shooting algorithm based on `HPIPM <href="https://github.com/giaf/hpipm"/>`__
15-
* **PISOC**\: Path integral stochastic optimal control
15+
* **IPM**\: Multiple-shooting algorithm based on nonlinear interior point method
16+
* **SLP**\: Sequential Linear Programming based on `PIPG <href="https://arxiv.org/abs/2009.06980"/>`__
1617

1718
OCS2 handles general path constraints through Augmented Lagrangian or
1819
relaxed barrier methods. To facilitate the application of OCS2 in robotic
@@ -51,18 +52,20 @@ Credits
5152
The following people have been involved in the development of OCS2:
5253

5354
**Project Manager**:
54-
Farbod Farshidian (ETHZ).
55+
Farbod Farshidian.
5556

5657
**Main Developers**:
57-
Farbod Farshidian (ETHZ),
58-
Ruben Grandia (ETHZ),
59-
Michael Spieler (ETHZ),
60-
Jan Carius (ETHZ),
61-
Jean-Pierre Sleiman (ETHZ).
58+
Farbod Farshidian,
59+
Ruben Grandia,
60+
Michael Spieler,
61+
Jan Carius,
62+
Jean-Pierre Sleiman.
6263

6364
**Other Developers**:
6465
Alexander Reske,
66+
Sotaro Katayama,
6567
Mayank Mittal,
68+
Jia-​Ruei Chiu,
6669
Johannes Pankert,
6770
Perry Franklin,
6871
Tom Lankhorst,
@@ -76,6 +79,25 @@ Edo Jelavic.
7679
project has continued to evolve at RSL, ETH Zurich. The RSL team now actively
7780
supports the development of OCS2.
7881

82+
Citing OCS2
83+
~~~~~~~~~~~
84+
To cite the toolbox in your academic research, please use the following:
85+
86+
.. code-block::
87+
88+
@misc{OCS2,
89+
title = {{OCS2}: An open source library for Optimal Control of Switched Systems},
90+
note = {[Online]. Available: \url{https://github.com/leggedrobotics/ocs2}},
91+
author = {Farbod Farshidian and others}
92+
}
93+
94+
Tutorials
95+
~~~~~~~~~
96+
* Tutorial on OCS2 Toolbox, Farbod Farshidian,
97+
MPC Workshop at RSS 2021 `link <href="https://youtu.be/RYmQN9GbFYg"/>`__
98+
* Real-time optimal control for legged locomotion & manipulation, Marco Hutter,
99+
MPC Workshop at RSS 2021 `link <href="https://youtu.be/sjAENmtO4bA"/>`__
100+
79101

80102
Related publications
81103
~~~~~~~~~~~~~~~~~~~~

ocs2_ipm/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@ include_directories(
5050
# Multiple shooting solver library
5151
add_library(${PROJECT_NAME}
5252
src/IpmHelpers.cpp
53+
src/IpmInitialization.cpp
5354
src/IpmPerformanceIndexComputation.cpp
5455
src/IpmSettings.cpp
5556
src/IpmSolver.cpp

ocs2_ipm/include/ocs2_ipm/IpmHelpers.h

+23
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
3030
#pragma once
3131

3232
#include <ocs2_core/Types.h>
33+
#include <ocs2_oc/multiple_shooting/Transcription.h>
34+
#include <ocs2_oc/oc_data/DualSolution.h>
35+
#include <ocs2_oc/oc_data/TimeDiscretization.h>
3336
#include <ocs2_oc/oc_problem/OptimalControlProblem.h>
3437

3538
namespace ocs2 {
@@ -107,5 +110,25 @@ vector_t retrieveDualDirection(scalar_t barrierParam, const vector_t& slack, con
107110
*/
108111
scalar_t fractionToBoundaryStepSize(const vector_t& v, const vector_t& dv, scalar_t marginRate = 0.995);
109112

113+
/**
114+
* Convert the optimized slack or dual trajectories as a DualSolution.
115+
*
116+
* @param time: The time discretization.
117+
* @param constraintsSize: The constraint tems size.
118+
* @param stateIneq: The slack/dual variable trajectory of the state inequality constraints.
119+
* @param stateInputIneq: The slack/dual variable trajectory of the state-input inequality constraints.
120+
* @return A dual solution.
121+
*/
122+
DualSolution toDualSolution(const std::vector<AnnotatedTime>& time, const std::vector<multiple_shooting::ConstraintsSize>& constraintsSize,
123+
const vector_array_t& stateIneq, const vector_array_t& stateInputIneq);
124+
125+
/**
126+
* Extracts slack/dual variables of the state-only and state-input constraints from a MultiplierCollection
127+
*
128+
* @param multiplierCollection: The MultiplierCollection.
129+
* @return slack/dual variables of the state-only (first) and state-input constraints (second).
130+
*/
131+
std::pair<vector_t, vector_t> fromMultiplierCollection(const MultiplierCollection& multiplierCollection);
132+
110133
} // namespace ipm
111134
} // namespace ocs2

ocs2_ipm/include/ocs2_ipm/IpmInitialization.h

+52-2
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
3030
#pragma once
3131

3232
#include <ocs2_core/Types.h>
33+
#include <ocs2_oc/oc_problem/OptimalControlProblem.h>
3334

3435
namespace ocs2 {
3536
namespace ipm {
@@ -44,7 +45,11 @@ namespace ipm {
4445
* @return Initialized slack variable.
4546
*/
4647
inline vector_t initializeSlackVariable(const vector_t& ineqConstraint, scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate) {
47-
return (1.0 + initialSlackMarginRate) * ineqConstraint.cwiseMax(initialSlackLowerBound);
48+
if (ineqConstraint.size() > 0) {
49+
return (1.0 + initialSlackMarginRate) * ineqConstraint.cwiseMax(initialSlackLowerBound);
50+
} else {
51+
return vector_t();
52+
}
4853
}
4954

5055
/**
@@ -59,8 +64,53 @@ inline vector_t initializeSlackVariable(const vector_t& ineqConstraint, scalar_t
5964
*/
6065
inline vector_t initializeDualVariable(const vector_t& slack, scalar_t barrierParam, scalar_t initialDualLowerBound,
6166
scalar_t initialDualMarginRate) {
62-
return (1.0 + initialDualMarginRate) * (barrierParam * slack.cwiseInverse()).cwiseMax(initialDualLowerBound);
67+
if (slack.size() > 0) {
68+
return (1.0 + initialDualMarginRate) * (barrierParam * slack.cwiseInverse()).cwiseMax(initialDualLowerBound);
69+
} else {
70+
return vector_t();
71+
}
6372
}
6473

74+
/**
75+
* Initializes the slack variable at a single intermediate node.
76+
*
77+
* @param ocpDefinition: Definition of the optimal control problem.
78+
* @param time : Time of this node
79+
* @param state : State
80+
* @param input : Input
81+
* @param initialSlackLowerBound : Lower bound of the initial slack variables. Corresponds to `slack_bound_push` option of IPOPT.
82+
* @param initialSlackMarginRate : Additional margin rate of the initial slack variables. Corresponds to `slack_bound_frac` option of IPOPT.
83+
* @return Initialized slack variables of the intermediate state-only (first) and state-input (second) constraints.
84+
*/
85+
std::pair<vector_t, vector_t> initializeIntermediateSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time,
86+
const vector_t& state, const vector_t& input,
87+
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate);
88+
89+
/**
90+
* Initializes the slack variable at the terminal node.
91+
*
92+
* @param ocpDefinition: Definition of the optimal control problem.
93+
* @param time : Time at the terminal node
94+
* @param state : Terminal state
95+
* @param initialSlackLowerBound : Lower bound of the initial slack variables. Corresponds to `slack_bound_push` option of IPOPT.
96+
* @param initialSlackMarginRate : Additional margin rate of the initial slack variables. Corresponds to `slack_bound_frac` option of IPOPT.
97+
* @return Initialized slack variable of the terminal state-only constraints.
98+
*/
99+
vector_t initializeTerminalSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time, const vector_t& state,
100+
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate);
101+
102+
/**
103+
* Initializes the slack variable at an event node.
104+
*
105+
* @param ocpDefinition: Definition of the optimal control problem.
106+
* @param time : Time at the event node
107+
* @param state : Pre-event state
108+
* @param initialSlackLowerBound : Lower bound of the initial slack variables. Corresponds to `slack_bound_push` option of IPOPT.
109+
* @param initialSlackMarginRate : Additional margin rate of the initial slack variables. Corresponds to `slack_bound_frac` option of IPOPT.
110+
* @return Initialized slack variable of the pre-jump state-only constraints.
111+
*/
112+
vector_t initializeEventSlackVariable(OptimalControlProblem& ocpDefinition, scalar_t time, const vector_t& state,
113+
scalar_t initialSlackLowerBound, scalar_t initialSlackMarginRate);
114+
65115
} // namespace ipm
66116
} // namespace ocs2

ocs2_ipm/include/ocs2_ipm/IpmSolver.h

+19-12
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
3535
#include <ocs2_core/thread_support/ThreadPool.h>
3636

3737
#include <ocs2_oc/multiple_shooting/ProjectionMultiplierCoefficients.h>
38+
#include <ocs2_oc/multiple_shooting/Transcription.h>
3839
#include <ocs2_oc/oc_data/TimeDiscretization.h>
3940
#include <ocs2_oc/oc_problem/OptimalControlProblem.h>
4041
#include <ocs2_oc/oc_solver/SolverBase.h>
@@ -66,6 +67,8 @@ class IpmSolver : public SolverBase {
6667

6768
void getPrimalSolution(scalar_t finalTime, PrimalSolution* primalSolutionPtr) const override { *primalSolutionPtr = primalSolution_; }
6869

70+
const DualSolution* getDualSolution() const override { return &dualIneqTrajectory_; }
71+
6972
const ProblemMetrics& getSolutionMetrics() const override { return problemMetrics_; }
7073

7174
size_t getNumIterations() const override { return totalNumIterations_; }
@@ -84,9 +87,7 @@ class IpmSolver : public SolverBase {
8487

8588
vector_t getStateInputEqualityConstraintLagrangian(scalar_t time, const vector_t& state) const override;
8689

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;
9091

9192
private:
9293
void runImpl(scalar_t initTime, const vector_t& initState, scalar_t finalTime) override;
@@ -123,12 +124,17 @@ class IpmSolver : public SolverBase {
123124
void initializeProjectionMultiplierTrajectory(const std::vector<AnnotatedTime>& timeDiscretization,
124125
vector_array_t& projectionMultiplierTrajectory) const;
125126

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+
126132
/** Creates QP around t, x(t), u(t). Returns performance metrics at the current {t, x(t), u(t)} */
127133
PerformanceIndex setupQuadraticSubproblem(const std::vector<AnnotatedTime>& time, const vector_t& initState, const vector_array_t& x,
128134
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);
132138

133139
/** Computes only the performance metrics at the current {t, x(t), u(t)} */
134140
PerformanceIndex computePerformance(const std::vector<AnnotatedTime>& time, const vector_t& initState, const vector_array_t& x,
@@ -142,15 +148,15 @@ class IpmSolver : public SolverBase {
142148
vector_array_t deltaLmdSol; // delta_lmd(t)
143149
vector_array_t deltaNuSol; // delta_nu(t)
144150
vector_array_t deltaSlackStateIneq;
145-
vector_array_t deltaSlackStateInputIneq;
146151
vector_array_t deltaDualStateIneq;
152+
vector_array_t deltaSlackStateInputIneq;
147153
vector_array_t deltaDualStateInputIneq;
148154
scalar_t armijoDescentMetric; // inner product of the cost gradient and decision variable step
149155
scalar_t maxPrimalStepSize;
150156
scalar_t maxDualStepSize;
151157
};
152158
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,
154160
const vector_array_t& dualStateInputIneq);
155161

156162
/** Extract the value function based on the last solved QP */
@@ -196,10 +202,8 @@ class IpmSolver : public SolverBase {
196202
PrimalSolution primalSolution_;
197203
vector_array_t costateTrajectory_;
198204
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_;
203207

204208
// Value function in absolute state coordinates (without the constant value)
205209
std::vector<ScalarFunctionQuadraticApproximation> valueFunction_;
@@ -212,6 +216,9 @@ class IpmSolver : public SolverBase {
212216
std::vector<VectorFunctionLinearApproximation> stateInputIneqConstraints_;
213217
std::vector<VectorFunctionLinearApproximation> constraintsProjection_;
214218

219+
// Constraint terms size
220+
std::vector<multiple_shooting::ConstraintsSize> constraintsSize_;
221+
215222
// Lagrange multipliers
216223
std::vector<multiple_shooting::ProjectionMultiplierCoefficients> projectionMultiplierCoefficients_;
217224

ocs2_ipm/src/IpmHelpers.cpp

+67
Original file line numberDiff line numberDiff line change
@@ -113,5 +113,72 @@ scalar_t fractionToBoundaryStepSize(const vector_t& v, const vector_t& dv, scala
113113
return alpha > 0.0 ? std::min(1.0 / alpha, 1.0) : 1.0;
114114
}
115115

116+
namespace {
117+
MultiplierCollection toMultiplierCollection(const multiple_shooting::ConstraintsSize constraintsSize, const vector_t& stateIneq) {
118+
MultiplierCollection multiplierCollection;
119+
size_t head = 0;
120+
for (const size_t size : constraintsSize.stateIneq) {
121+
multiplierCollection.stateIneq.emplace_back(0.0, stateIneq.segment(head, size));
122+
head += size;
123+
}
124+
return multiplierCollection;
125+
}
126+
127+
MultiplierCollection toMultiplierCollection(const multiple_shooting::ConstraintsSize constraintsSize, const vector_t& stateIneq,
128+
const vector_t& stateInputIneq) {
129+
MultiplierCollection multiplierCollection = toMultiplierCollection(constraintsSize, stateIneq);
130+
size_t head = 0;
131+
for (const size_t size : constraintsSize.stateInputIneq) {
132+
multiplierCollection.stateInputIneq.emplace_back(0.0, stateInputIneq.segment(head, size));
133+
head += size;
134+
}
135+
return multiplierCollection;
136+
}
137+
138+
vector_t extractLagrangian(const std::vector<Multiplier>& termsMultiplier) {
139+
size_t n = 0;
140+
std::for_each(termsMultiplier.begin(), termsMultiplier.end(), [&](const Multiplier& m) { n += m.lagrangian.size(); });
141+
142+
vector_t vec(n);
143+
size_t head = 0;
144+
for (const auto& m : termsMultiplier) {
145+
vec.segment(head, m.lagrangian.size()) = m.lagrangian;
146+
head += m.lagrangian.size();
147+
} // end of i loop
148+
149+
return vec;
150+
}
151+
} // namespace
152+
153+
DualSolution toDualSolution(const std::vector<AnnotatedTime>& time, const std::vector<multiple_shooting::ConstraintsSize>& constraintsSize,
154+
const vector_array_t& stateIneq, const vector_array_t& stateInputIneq) {
155+
// Problem horizon
156+
const int N = static_cast<int>(time.size()) - 1;
157+
158+
DualSolution dualSolution;
159+
dualSolution.timeTrajectory = toInterpolationTime(time);
160+
dualSolution.postEventIndices = toPostEventIndices(time);
161+
162+
dualSolution.preJumps.reserve(dualSolution.postEventIndices.size());
163+
dualSolution.intermediates.reserve(time.size());
164+
165+
for (int i = 0; i < N; ++i) {
166+
if (time[i].event == AnnotatedTime::Event::PreEvent) {
167+
dualSolution.preJumps.emplace_back(toMultiplierCollection(constraintsSize[i], stateIneq[i]));
168+
dualSolution.intermediates.push_back(dualSolution.intermediates.back()); // no event at the initial node
169+
} else {
170+
dualSolution.intermediates.emplace_back(toMultiplierCollection(constraintsSize[i], stateIneq[i], stateInputIneq[i]));
171+
}
172+
}
173+
dualSolution.final = toMultiplierCollection(constraintsSize[N], stateIneq[N]);
174+
dualSolution.intermediates.push_back(dualSolution.intermediates.back());
175+
176+
return dualSolution;
177+
}
178+
179+
std::pair<vector_t, vector_t> fromMultiplierCollection(const MultiplierCollection& multiplierCollection) {
180+
return std::make_pair(extractLagrangian(multiplierCollection.stateIneq), extractLagrangian(multiplierCollection.stateInputIneq));
181+
}
182+
116183
} // namespace ipm
117184
} // namespace ocs2

0 commit comments

Comments
 (0)