final_state_conditions_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  Eigen::Ref<Eigen::VectorXd> cost) const
33 {
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 (_diagonal_mode)
41  cost.noalias() = _Qf_diag_sqrt * xd;
42  else
43  cost.noalias() = _Qf_sqrt * xd;
44  }
45  else
46  {
47  if (_diagonal_mode)
48  cost.noalias() = xd.transpose() * _Qf_diag * xd;
49  else
50  cost.noalias() = xd.transpose() * _Qf * xd;
51  }
52 }
53 
55 {
56  assert(cost.size() == getNonIntegralStateTermDimension(k));
57 
58  Eigen::VectorXd xd = x_k - _x_ref->getReferenceCached(k);
59  xd[2] = normalize_theta(xd[2]);
60  if (_diagonal_mode)
61  cost[0] = xd.transpose() * _S_diag * xd - _gamma;
62  else
63  cost[0] = xd.transpose() * _S * xd - _gamma;
64 }
65 
66 } // namespace mpc_local_planner
corbo::TerminalBall::_gamma
double _gamma
corbo::TerminalBall::_diagonal_mode
bool _diagonal_mode
corbo::ReferenceTrajectoryInterface::getReferenceCached
virtual const OutputVector & getReferenceCached(int k) const=0
corbo::QuadraticFinalStateCost::_Qf_diag
Eigen::DiagonalMatrix< double, -1 > _Qf_diag
mpc_local_planner::QuadraticFinalStateCostSE2::computeNonIntegralStateTerm
void computeNonIntegralStateTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: final_state_conditions_se2.cpp:51
corbo::QuadraticFinalStateCost::_lsq_form
bool _lsq_form
mpc_local_planner
Definition: controller.h:44
corbo::QuadraticFinalStateCost::getNonIntegralStateTermDimension
int getNonIntegralStateTermDimension(int k) const override
corbo::QuadraticFinalStateCost::_diagonal_mode
bool _diagonal_mode
corbo::QuadraticFinalStateCost::_Qf_sqrt
Eigen::MatrixXd _Qf_sqrt
corbo::QuadraticFinalStateCost::_x_ref
const ReferenceTrajectoryInterface * _x_ref
corbo::TerminalBall::getNonIntegralStateTermDimension
int getNonIntegralStateTermDimension(int k) const override
mpc_local_planner::TerminalBallSE2::computeNonIntegralStateTerm
void computeNonIntegralStateTerm(int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: final_state_conditions_se2.cpp:74
corbo::TerminalBall::_S_diag
Eigen::DiagonalMatrix< double, -1 > _S_diag
final_state_conditions_se2.h
corbo::QuadraticFinalStateCost::_Qf_diag_sqrt
Eigen::DiagonalMatrix< double, -1 > _Qf_diag_sqrt
Eigen::Ref
mpc_local_planner::normalize_theta
double normalize_theta(double theta)
normalize angle to interval [-pi, pi)
Definition: math_utils.h:101
corbo::QuadraticFinalStateCost::_Qf
Eigen::MatrixXd _Qf
math_utils.h
corbo::TerminalBall::_x_ref
const ReferenceTrajectoryInterface * _x_ref
corbo::TerminalBall::_S
Eigen::MatrixXd _S


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06