minimum_time.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_MINIMUM_TIME_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_MINIMUM_TIME_H_
27 
29 
30 #include <cmath>
31 #include <memory>
32 
33 namespace corbo {
34 
35 class MinimumTime : public StageCost
36 {
37  public:
38  using Ptr = std::shared_ptr<MinimumTime>;
39 
40  MinimumTime() = default;
41 
42  MinimumTime(bool lsq_form) : _lsq_form(lsq_form) {}
43 
44  StageCost::Ptr getInstance() const override { return std::make_shared<MinimumTime>(); }
45 
46  bool hasNonIntegralTerms(int k) const override { return true; }
47  bool hasIntegralTerms(int k) const override { return false; }
48 
49  int getNonIntegralDtTermDimension(int k) const override { return (k == 0 || !_single_dt) ? 1 : 0; }
50  bool isLsqFormNonIntegralDtTerm(int k) const override { return _lsq_form; }
51 
52  bool update(int n, double /*t*/, ReferenceTrajectoryInterface& /*xref*/, ReferenceTrajectoryInterface& /*uref*/,
53  ReferenceTrajectoryInterface* /*sref*/, bool single_dt, const Eigen::VectorXd& x0, StagePreprocessor::Ptr stage_preprocessor,
54  const std::vector<double>& dts, const DiscretizationGridInterface* /*grid*/) override
55  {
56  if (!_custom_weight)
57  {
58  _single_dt = single_dt;
59  if (single_dt)
60  _weight = _lsq_form ? std::sqrt(n - 1) : (n - 1);
61  else
62  {
63  _weight = _lsq_form ? std::sqrt(n - 1) : 1.0;
64  // _weight = 1.0;
65  }
66  }
67  return false;
68  }
69 
70  void computeNonIntegralDtTerm(int k, double dt, Eigen::Ref<Eigen::VectorXd> cost) const override
71  {
72  if (!_single_dt || k == 0)
73  cost[0] = _weight * dt;
74  else
75  {
76  PRINT_DEBUG_NAMED("this method should not be called in single_dt mode and k>0");
77  }
78  }
79 
80  void setCustomWeight(double weight)
81  {
83  _weight = weight;
84  }
85  double getCustomWeight() const { return _weight; }
86 
87  void setLsqForm(bool lsq_form) { _lsq_form = lsq_form; }
88 
89 #ifdef MESSAGE_SUPPORT
90  virtual bool fromMessage(const messages::MinimumTime& message, std::stringstream* issues)
91  {
92  _lsq_form = message.lsq_form();
93  return true;
94  }
95  virtual void toMessage(messages::MinimumTime& message) const { message.set_lsq_form(_lsq_form); }
96 
97  bool fromMessage(const messages::StageCost& message, std::stringstream* issues) override { return fromMessage(message.minimum_time(), issues); }
98  void toMessage(messages::StageCost& message) const override { toMessage(*message.mutable_minimum_time()); }
99 #endif
100 
101  protected:
102  bool _lsq_form = false;
103  double _weight = 1.0;
104  bool _single_dt = false;
105  bool _custom_weight = false;
106 };
107 FACTORY_REGISTER_STAGE_COST(MinimumTime)
108 
109 class MinimumTimeRegularized : public StageCost
110 {
111  public:
112  using Ptr = std::shared_ptr<MinimumTimeRegularized>;
113 
115 
116  StageCost::Ptr getInstance() const override { return std::make_shared<MinimumTimeRegularized>(); }
117 
118  bool hasNonIntegralTerms(int k) const override { return true; }
119  bool hasIntegralTerms(int k) const override { return false; }
120 
121  int getNonIntegralDtTermDimension(int k) const override { return 1; }
122  bool isLsqFormNonIntegralDtTerm(int k) const override { return false; }
123 
124  bool update(int n, double /*t*/, ReferenceTrajectoryInterface& /*xref*/, ReferenceTrajectoryInterface& /*uref*/,
125  ReferenceTrajectoryInterface* /*sref*/, bool /*single_dt*/, const Eigen::VectorXd& /*x0*/,
126  StagePreprocessor::Ptr /*stage_preprocessor*/, const std::vector<double>& /*dts*/,
127  const DiscretizationGridInterface* /*grid*/) override
128  {
129  return false;
130  }
131 
132  void computeNonIntegralDtTerm(int k, double dt, Eigen::Ref<Eigen::VectorXd> cost) const override { cost[0] = dt + _reg_factor * dt * dt; }
133 
134  void setRegularizationFactor(double reg_factor) { _reg_factor = reg_factor; }
135 
136 #ifdef MESSAGE_SUPPORT
137  virtual bool fromMessage(const messages::MinimumTimeRegularized& message, std::stringstream* issues)
138  {
139  _reg_factor = message.reg_factor();
140  return true;
141  }
142  virtual void toMessage(messages::MinimumTimeRegularized& message) const { message.set_reg_factor(_reg_factor); }
143 
144  bool fromMessage(const messages::StageCost& message, std::stringstream* issues) override
145  {
146  return fromMessage(message.minimum_time_regularized(), issues);
147  }
148  void toMessage(messages::StageCost& message) const override { toMessage(*message.mutable_minimum_time_regularized()); }
149 #endif
150 
151  protected:
152  double _reg_factor = 0.0;
153 };
155 
156 } // namespace corbo
157 
158 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_FUNCTIONS_MINIMUM_TIME_H_
sqrt
const EIGEN_DEVICE_FUNC SqrtReturnType sqrt() const
Definition: ArrayCwiseUnaryOps.h:152
corbo::MinimumTimeRegularized::_reg_factor
double _reg_factor
Definition: minimum_time.h:174
corbo::MinimumTimeRegularized::getInstance
StageCost::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: minimum_time.h:138
corbo::StagePreprocessor::Ptr
std::shared_ptr< StagePreprocessor > Ptr
Definition: stage_preprocessor.h:66
corbo::MinimumTime::Ptr
std::shared_ptr< MinimumTime > Ptr
Definition: minimum_time.h:82
corbo::ReferenceTrajectoryInterface
Interface class for reference trajectories.
Definition: reference_trajectory.h:82
corbo::MinimumTime::setCustomWeight
void setCustomWeight(double weight)
Definition: minimum_time.h:124
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::MinimumTime::_single_dt
bool _single_dt
Definition: minimum_time.h:148
corbo::MinimumTime::update
bool update(int n, double, ReferenceTrajectoryInterface &, ReferenceTrajectoryInterface &, ReferenceTrajectoryInterface *, bool single_dt, const Eigen::VectorXd &x0, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *) override
Definition: minimum_time.h:96
corbo::MinimumTimeRegularized::isLsqFormNonIntegralDtTerm
bool isLsqFormNonIntegralDtTerm(int k) const override
Definition: minimum_time.h:144
corbo::MinimumTimeRegularized::hasNonIntegralTerms
bool hasNonIntegralTerms(int k) const override
Definition: minimum_time.h:140
corbo::MinimumTime::computeNonIntegralDtTerm
void computeNonIntegralDtTerm(int k, double dt, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: minimum_time.h:114
corbo::StageCost::Ptr
std::shared_ptr< StageCost > Ptr
Definition: stage_functions.h:155
corbo::MinimumTime::hasIntegralTerms
bool hasIntegralTerms(int k) const override
Definition: minimum_time.h:91
corbo::MinimumTime::_weight
double _weight
Definition: minimum_time.h:147
PRINT_DEBUG_NAMED
#define PRINT_DEBUG_NAMED(msg)
Definition: console.h:245
corbo::MinimumTimeRegularized::Ptr
std::shared_ptr< MinimumTimeRegularized > Ptr
Definition: minimum_time.h:134
corbo::MinimumTime::isLsqFormNonIntegralDtTerm
bool isLsqFormNonIntegralDtTerm(int k) const override
Definition: minimum_time.h:94
stage_functions.h
corbo::MinimumTimeRegularized::computeNonIntegralDtTerm
void computeNonIntegralDtTerm(int k, double dt, Eigen::Ref< Eigen::VectorXd > cost) const override
Definition: minimum_time.h:154
corbo::MinimumTime::_custom_weight
bool _custom_weight
Definition: minimum_time.h:149
FACTORY_REGISTER_STAGE_COST
#define FACTORY_REGISTER_STAGE_COST(type)
Definition: stage_functions.h:170
corbo::MinimumTimeRegularized
Definition: minimum_time.h:131
corbo::MinimumTimeRegularized::MinimumTimeRegularized
MinimumTimeRegularized()=default
corbo::MinimumTime::MinimumTime
MinimumTime()=default
corbo::MinimumTime::getInstance
StageCost::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: minimum_time.h:88
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::MinimumTime::_lsq_form
bool _lsq_form
Definition: minimum_time.h:146
corbo::MinimumTime::getCustomWeight
double getCustomWeight() const
Definition: minimum_time.h:129
corbo::MinimumTime::setLsqForm
void setLsqForm(bool lsq_form)
Definition: minimum_time.h:131
corbo::MinimumTimeRegularized::update
bool update(int n, double, ReferenceTrajectoryInterface &, ReferenceTrajectoryInterface &, ReferenceTrajectoryInterface *, bool, const Eigen::VectorXd &, StagePreprocessor::Ptr, const std::vector< double > &, const DiscretizationGridInterface *) override
Definition: minimum_time.h:146
corbo::MinimumTime::hasNonIntegralTerms
bool hasNonIntegralTerms(int k) const override
Definition: minimum_time.h:90
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::MinimumTimeRegularized::setRegularizationFactor
void setRegularizationFactor(double reg_factor)
Definition: minimum_time.h:156
corbo::MinimumTimeRegularized::getNonIntegralDtTermDimension
int getNonIntegralDtTermDimension(int k) const override
Definition: minimum_time.h:143
corbo::MinimumTime::getNonIntegralDtTermDimension
int getNonIntegralDtTermDimension(int k) const override
Definition: minimum_time.h:93
corbo::MinimumTimeRegularized::hasIntegralTerms
bool hasIntegralTerms(int k) const override
Definition: minimum_time.h:141
corbo::DiscretizationGridInterface
Generic interface class for discretization grids.
Definition: discretization_grid_interface.h:104


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:58