quadratic_cost_se2.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
24 
26 
27 #include <cmath>
28 
29 namespace mpc_local_planner {
30 
32 {
33  assert(!_integral_form);
34  assert(cost.size() == getNonIntegralStateTermDimension(k));
35 
36  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
37  xd[2] = normalize_theta(xd[2]);
38  if (_lsq_form)
39  {
40  if (_Q_diagonal_mode)
41  cost.noalias() = _Q_diag_sqrt * xd;
42  else
43  cost.noalias() = _Q_sqrt * xd;
44  }
45  else
46  {
47  if (_Q_diagonal_mode)
48  cost.noalias() = xd.transpose() * _Q_diag * xd;
49  else
50  cost.noalias() = xd.transpose() * _Q * xd;
51  }
52 }
53 
56 {
57  assert(_integral_form);
58  assert(cost.size() == 1);
59 
60  cost[0] = 0;
61 
62  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
63  xd[2] = normalize_theta(xd[2]);
64  if (_Q_diagonal_mode)
65  cost[0] += xd.transpose() * _Q_diag * xd;
66  else
67  cost[0] += xd.transpose() * _Q * xd;
68 
69  if (_zero_u_ref)
70  {
71  if (_R_diagonal_mode)
72  cost[0] += u_k.transpose() * _R_diag * u_k;
73  else
74  cost[0] += u_k.transpose() * _R * u_k;
75  }
76  else
77  {
78  Eigen::VectorXd ud = u_k - _u_ref->getReferenceCached(k);
79  if (_R_diagonal_mode)
80  cost[0] += ud.transpose() * _R_diag * ud;
81  else
82  cost[0] += ud.transpose() * _R * ud;
83  }
84 }
85 
87 {
88  assert(!_integral_form);
89  assert(cost.size() == getNonIntegralStateTermDimension(k));
90 
91  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
92  xd[2] = normalize_theta(xd[2]);
93  if (_lsq_form)
94  {
95  if (_diagonal_mode)
96  cost.noalias() = _Q_diag_sqrt * xd;
97  else
98  cost.noalias() = _Q_sqrt * xd;
99  }
100  else
101  {
102  if (_diagonal_mode)
103  cost.noalias() = xd.transpose() * _Q_diag * xd;
104  else
105  cost.noalias() = xd.transpose() * _Q * xd;
106  }
107 }
108 
111 {
112  assert(_integral_form);
113  assert(cost.size() == 1);
114 
115  cost[0] = 0;
116 
117  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
118  xd[2] = normalize_theta(xd[2]);
119  if (_diagonal_mode)
120  cost[0] += xd.transpose() * _Q_diag * xd;
121  else
122  cost[0] += xd.transpose() * _Q * xd;
123 }
124 
125 } // namespace mpc_local_planner
Eigen::DiagonalMatrix< double, -1 > _Q_diag_sqrt
void computeIntegralStateControlTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) const override
void computeNonIntegralStateTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
const ReferenceTrajectoryInterface * _x_ref
virtual const OutputVector & getReferenceCached(int k) const=0
Eigen::DiagonalMatrix< double, -1 > _Q_diag
void computeNonIntegralStateTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Eigen::MatrixXd _Q_sqrt
void computeIntegralStateControlTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, Eigen::Ref< Eigen::VectorXd > cost) const override
int getNonIntegralStateTermDimension(int k) const override
double normalize_theta(double theta)
normalize angle to interval [-pi, pi)
Definition: math_utils.h:81
Eigen::DiagonalMatrix< double, -1 > _R_diag
const ReferenceTrajectoryInterface * _u_ref


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:53:18