aligator 0.18.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
utils.hpp
Go to the documentation of this file.
1
2#pragma once
3
4#include "lqr-problem.hpp"
6
7#include <Eigen/SparseCore>
8
9namespace aligator::gar {
10namespace helpers {
13template <typename InType, typename OutScalar>
14void sparseAssignDenseBlock(Eigen::Index i0, Eigen::Index j0,
15 const Eigen::DenseBase<InType> &input,
16 Eigen::SparseMatrix<OutScalar> &out, bool update) {
17 assert(i0 + input.rows() <= out.rows() && "Inconsistent rows");
18 assert(j0 + input.cols() <= out.cols() && "Inconsistent cols");
19 using Eigen::Index;
20 for (Index i = 0; i < input.rows(); i++) {
21 for (Index j = 0; j < input.cols(); j++) {
22 if (update)
23 out.coeffRef(i0 + i, j0 + j) = input(i, j);
24 else
25 out.insert(i0 + i, j0 + j) = input(i, j);
26 }
27 }
28}
29
30template <typename Scalar>
31void sparseAssignDiagonal(Eigen::Index i0, Eigen::Index i1, Scalar value,
32 Eigen::SparseMatrix<Scalar> &out, bool update) {
33 using Eigen::Index;
34 assert(i0 <= i1 && "i0 should be lesser than i1. Can't assign empty range.");
35 assert(i1 <= out.rows() && "Inconsistent rows");
36 assert(i1 <= out.cols() && "Inconsistent cols");
37 for (Index kk = i0; kk < i1; kk++) {
38 if (update)
39 out.coeffRef(kk, kk) = value;
40 else
41 out.insert(kk, kk) = value;
42 }
43}
44} // namespace helpers
45
46template <typename Scalar>
48 const Scalar mueq, Eigen::SparseMatrix<Scalar> &mat,
49 Eigen::Matrix<Scalar, -1, 1> &rhs, bool update);
50
51template <typename Scalar>
52[[nodiscard]] std::array<Scalar, 3> lqrComputeKktError(
53 const LqrProblemTpl<Scalar> &problem,
54 boost::span<const typename math_types<Scalar>::VectorXs> xs,
55 boost::span<const typename math_types<Scalar>::VectorXs> us,
56 boost::span<const typename math_types<Scalar>::VectorXs> vs,
57 boost::span<const typename math_types<Scalar>::VectorXs> lbdas,
58 const Scalar mueq,
59 const std::optional<typename math_types<Scalar>::ConstVectorRef> &theta =
60 std::nullopt,
61 bool verbose = false);
62
64template <typename Scalar>
66 const auto &knots = problem.stages;
67 const uint nc0 = problem.nc0();
68 const size_t N = knots.size() - 1UL;
69 uint nrows = nc0;
70 for (size_t t = 0; t <= N; t++) {
71 const auto &model = knots[t];
72 nrows += model.nx + model.nu + model.nc;
73 if (t != N)
74 nrows += model.nx;
75 }
76 return nrows;
77}
78
80template <typename Scalar>
82 const LqrProblemTpl<Scalar> &problem,
83 const typename math_types<Scalar>::ConstVectorRef solution,
84 std::vector<typename math_types<Scalar>::VectorXs> &xs,
85 std::vector<typename math_types<Scalar>::VectorXs> &us,
86 std::vector<typename math_types<Scalar>::VectorXs> &vs,
87 std::vector<typename math_types<Scalar>::VectorXs> &lbdas) {
88 const uint N = (uint)problem.horizon();
89 xs.resize(N + 1);
90 us.resize(N + 1);
91 vs.resize(N + 1);
92 lbdas.resize(N + 1);
93 const uint nc0 = problem.nc0();
94
95 lbdas[0] = solution.head(nc0);
96
97 uint idx = nc0;
98 for (size_t t = 0; t <= N; t++) {
99 const LqrKnotTpl<Scalar> &knot = problem.stages[t];
100 const uint n = knot.nx + knot.nu + knot.nc;
101 auto seg = solution.segment(idx, n);
102 xs[t] = seg.head(knot.nx);
103 us[t] = seg.segment(knot.nx, knot.nu);
104 vs[t] = seg.segment(knot.nx + knot.nu, knot.nc);
105 idx += n;
106 if (t < N) {
107 lbdas[t + 1] = solution.segment(idx, knot.nx2);
108 idx += knot.nx2;
109 }
110 }
111}
112
113template <typename Scalar>
114[[nodiscard]] auto lqrInitializeSolution(const LqrProblemTpl<Scalar> &problem) {
115 using VectorXs = typename math_types<Scalar>::VectorXs;
116 std::vector<VectorXs> xs;
117 std::vector<VectorXs> us;
118 std::vector<VectorXs> vs;
119 std::vector<VectorXs> lbdas;
120 const uint N = (uint)problem.horizon();
121
122 xs.resize(N + 1);
123 us.resize(N + 1);
124 vs.resize(N + 1);
125 lbdas.resize(N + 1);
126
127 lbdas[0].setZero(problem.nc0());
128 for (uint i = 0; i <= N; i++) {
129 const LqrKnotTpl<Scalar> &kn = problem.stages[i];
130 xs[i].setZero(kn.nx);
131 us[i].setZero(kn.nu);
132 vs[i].setZero(kn.nc);
133 if (i == N)
134 break;
135 lbdas[i + 1].setZero(kn.nx2);
136 }
137 if (problem.stages.back().nu == 0) {
138 us.pop_back();
139 }
140 return std::make_tuple(std::move(xs), std::move(us), std::move(vs),
141 std::move(lbdas));
142}
143
144#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
145extern template void lqrCreateSparseMatrix<context::Scalar>(
146 const LqrProblemTpl<context::Scalar> &problem, const context::Scalar mueq,
147 Eigen::SparseMatrix<context::Scalar> &mat, context::VectorXs &rhs,
148 bool update);
149extern template std::array<context::Scalar, 3>
151 const LqrProblemTpl<context::Scalar> &,
152 boost::span<const context::VectorXs>, boost::span<const context::VectorXs>,
153 boost::span<const context::VectorXs>, boost::span<const context::VectorXs>,
154 const context::Scalar, const std::optional<context::ConstVectorRef> &,
155 bool);
156#endif
157
158} // namespace aligator::gar
void sparseAssignDiagonal(Eigen::Index i0, Eigen::Index i1, Scalar value, Eigen::SparseMatrix< Scalar > &out, bool update)
Definition utils.hpp:31
void sparseAssignDenseBlock(Eigen::Index i0, Eigen::Index j0, const Eigen::DenseBase< InType > &input, Eigen::SparseMatrix< OutScalar > &out, bool update)
Helper to assign a dense matrix into a range of coefficients of a sparse matrix.
Definition utils.hpp:14
void lqrCreateSparseMatrix(const LqrProblemTpl< Scalar > &problem, const Scalar mueq, Eigen::SparseMatrix< Scalar > &mat, Eigen::Matrix< Scalar, -1, 1 > &rhs, bool update)
auto lqrInitializeSolution(const LqrProblemTpl< Scalar > &problem)
Definition utils.hpp:114
void lqrDenseSolutionToTraj(const LqrProblemTpl< Scalar > &problem, const typename math_types< Scalar >::ConstVectorRef solution, std::vector< typename math_types< Scalar >::VectorXs > &xs, std::vector< typename math_types< Scalar >::VectorXs > &us, std::vector< typename math_types< Scalar >::VectorXs > &vs, std::vector< typename math_types< Scalar >::VectorXs > &lbdas)
Convert dense RHS solution to its trajectory [x,u,v,lambda] solution.
Definition utils.hpp:81
std::array< Scalar, 3 > lqrComputeKktError(const LqrProblemTpl< Scalar > &problem, boost::span< const typename math_types< Scalar >::VectorXs > xs, boost::span< const typename math_types< Scalar >::VectorXs > us, boost::span< const typename math_types< Scalar >::VectorXs > vs, boost::span< const typename math_types< Scalar >::VectorXs > lbdas, const Scalar mueq, const std::optional< typename math_types< Scalar >::ConstVectorRef > &theta=std::nullopt, bool verbose=false)
uint lqrNumRows(const LqrProblemTpl< Scalar > &problem)
Compute the number of rows in the problem matrix.
Definition utils.hpp:65
unsigned int uint
Definition logger.hpp:11
Struct describing a stage of a constrained LQ problem.
int horizon() const noexcept
uint nc0() const noexcept
Dimension of the initial condition constraint.
Typedefs for math (Eigen vectors, matrices) depending on scalar type.
Definition math.hpp:122