vector_vertex_se2.h
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 
23 #ifndef VECTOR_SE_VERTEX_H_
24 #define VECTOR_SE_VERTEX_H_
25 
27 
29 
30 #include <corbo-core/types.h>
31 
32 #include <memory>
33 #include <vector>
34 
35 namespace mpc_local_planner {
36 
54 class VectorVertexSE2 : public corbo::VectorVertex
55 {
56  public:
57  using Ptr = std::shared_ptr<VectorVertexSE2>;
58  using UPtr = std::unique_ptr<VectorVertexSE2>;
59 
61  VectorVertexSE2() = default;
62 
63  explicit VectorVertexSE2(bool fixed) : corbo::VectorVertex(fixed) {}
64 
66  explicit VectorVertexSE2(int dimension, bool fixed = false) : VectorVertex(dimension, fixed) {}
67 
69  explicit VectorVertexSE2(const Eigen::Ref<const Eigen::VectorXd>& values, bool fixed = false) : VectorVertex(values, fixed) {}
70 
73  const Eigen::Ref<const Eigen::VectorXd>& ub, bool fixed = false)
74  : VectorVertex(values, lb, ub, fixed)
75  {
76  }
77 
78  // implements interface method
79  void plus(int idx, double inc) override
80  {
81  if (idx == 2)
82  _values[idx] = normalize_theta(_values[idx] + inc);
83  else
84  _values[idx] += inc;
85  }
86  // implements interface method
87  void plus(const double* inc) override
88  {
89  assert(getDimension() >= 3);
90  _values[0] += inc[0];
91  _values[1] += inc[1];
92  _values[2] = normalize_theta(_values[2] + inc[2]);
93  if (getDimension() > 3) _values.tail(getDimension() - 3) += Eigen::Map<const Eigen::VectorXd>(inc + 3, getDimension() - 3);
94  }
95  // implements interface method
96  void plusUnfixed(const double* inc) override { plus(inc); }
97 
98  // implements interface method
99  void setData(int idx, double data) override
100  {
101  if (idx == 2)
102  _values[idx] = normalize_theta(data);
103  else
104  _values[idx] = data;
105  }
106 
109  const Eigen::Ref<const Eigen::VectorXd>& ub, bool fixed = false)
110  {
111  assert(values.size() == lb.size());
112  assert(values.size() == ub.size());
113  assert(values.size() >= 3);
114  _values = values;
116  setLowerBounds(lb);
117  setUpperBounds(ub);
118 
119  setFixed(false);
120  }
121 
122  public:
124 };
125 
138 class PartiallyFixedVectorVertexSE2 : public VectorVertexSE2
139 {
140  public:
141  using Ptr = std::shared_ptr<PartiallyFixedVectorVertexSE2>;
142  using UPtr = std::unique_ptr<PartiallyFixedVectorVertexSE2>;
143 
145  PartiallyFixedVectorVertexSE2() = default;
146 
147  explicit PartiallyFixedVectorVertexSE2(int dimension)
148  : VectorVertexSE2(dimension), _fixed(Eigen::Array<bool, -1, 1>::Constant(dimension, false)), _num_unfixed(dimension)
149  {
150  }
151 
153  explicit PartiallyFixedVectorVertexSE2(int dimension, const Eigen::Ref<const Eigen::Array<bool, -1, 1>>& fixed)
154  : VectorVertexSE2(dimension), _fixed(fixed), _num_unfixed(dimension)
155  {
156  }
157 
160  : VectorVertexSE2(values), _fixed(Eigen::Array<bool, -1, 1>::Constant(values.size(), false)), _num_unfixed(values.size())
161  {
162  }
163 
166  : VectorVertexSE2(values), _fixed(fixed), _num_unfixed(fixed.size() - fixed.count())
167  {
168  }
169 
173  : VectorVertexSE2(values, lb, ub), _fixed(Eigen::Array<bool, -1, 1>::Constant(values.size(), false)), _num_unfixed(values.size())
174  {
175  }
176 
177  // implements interface method
178  int getDimensionUnfixed() const override { return _num_unfixed; }
179 
180  // implements parent method
181  void setDimension(int dim) override
182  {
184  _fixed.setConstant(dim, false);
186  }
187 
190  const Eigen::Ref<const Eigen::VectorXd>& ub, bool fixed = false) override
191  {
192  assert(values.size() == lb.size());
193  assert(values.size() == ub.size());
194  assert(values.size() >= 3);
195  _values = values;
197  setLowerBounds(lb);
199 
200  setFixed(fixed);
201  }
202 
206  {
207  assert(values.size() == lb.size());
208  assert(values.size() == ub.size());
209  assert(values.size() >= 3);
210  _values = values;
212  setLowerBounds(lb);
213  setUpperBounds(ub);
214 
215  setFixed(fixed);
216  }
217 
219  void setFixed(int idx, bool fixed)
220  {
221  _fixed[idx] = fixed;
222  _num_unfixed = getDimension() - _fixed.count();
223  }
224 
226  void setFixed(const Eigen::Ref<const Eigen::Array<bool, -1, 1>>& fixed)
227  {
228  _fixed = fixed;
229  _num_unfixed = getDimension() - _fixed.count();
230  }
231 
232  // implements interface method
233  void setFixed(bool fixed) override
234  {
235  _fixed.setConstant(_values.size(), fixed);
236  _num_unfixed = fixed ? 0 : getDimension();
237  }
238 
239  // implements interface method
240  void plusUnfixed(const double* inc) override
241  {
242  int idx = 0;
243  for (int i = 0; i < getDimension(); ++i)
244  {
245  if (!_fixed(i))
246  {
247  plus(i, inc[idx]);
248  ++idx;
249  }
250  }
251  }
252 
253  // implements interface method
254  bool hasFixedComponents() const override { return _num_unfixed < getDimension(); }
255  // implements interface method
256  bool isFixedComponent(int idx) const override { return _fixed[idx]; }
257 
258  // implements interface method
259  int getNumberFiniteLowerBounds(bool unfixed_only) const override
260  {
261  if (unfixed_only && _num_unfixed > 0)
262  {
263  int num = 0;
264  for (int i = 0; i < getDimension(); ++i)
265  {
266  if (!_fixed[i] && _lb[i] > -corbo::CORBO_INF_DBL) num += 1;
267  }
268  return num;
269  }
270  else
271  return (_lb.array() > -corbo::CORBO_INF_DBL).count();
272  }
273 
274  // implements interface method
275  int getNumberFiniteUpperBounds(bool unfixed_only) const override
276  {
277  if (unfixed_only && _num_unfixed > 0)
278  {
279  int num = 0;
280  for (int i = 0; i < getDimension(); ++i)
281  {
282  if (!_fixed[i] && _ub[i] < corbo::CORBO_INF_DBL) num += 1;
283  }
284  return num;
285  }
286  else
287  return (_ub.array() < corbo::CORBO_INF_DBL).count();
288  }
289 
290  // implements interface method
291  int getNumberFiniteBounds(bool unfixed_only) const override
292  {
293  if (unfixed_only && _num_unfixed > 0)
294  {
295  int num = 0;
296  for (int i = 0; i < getDimension(); ++i)
297  {
298  if (!_fixed[i] && (_ub[i] < corbo::CORBO_INF_DBL || _lb[i] > -corbo::CORBO_INF_DBL)) num += 1;
299  }
300  return num;
301  }
302  else
303  return (_ub.array() < corbo::CORBO_INF_DBL || _lb.array() > -corbo::CORBO_INF_DBL).count();
304  }
305 
307  const Eigen::Array<bool, -1, 1> fixedArray() const { return _fixed; }
308 
309  protected:
310  Eigen::Array<bool, -1, 1> _fixed;
312 };
313 
314 } // namespace mpc_local_planner
315 
316 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_VECTOR_VERTEX_H_
mpc_local_planner::PartiallyFixedVectorVertexSE2::getNumberFiniteBounds
int getNumberFiniteBounds(bool unfixed_only) const override
Definition: vector_vertex_se2.h:311
corbo::VectorVertex::setUpperBounds
void setUpperBounds(const Eigen::Ref< const Eigen::VectorXd > &ub) override
Eigen
mpc_local_planner::PartiallyFixedVectorVertexSE2::getNumberFiniteUpperBounds
int getNumberFiniteUpperBounds(bool unfixed_only) const override
Definition: vector_vertex_se2.h:295
mpc_local_planner::PartiallyFixedVectorVertexSE2::hasFixedComponents
bool hasFixedComponents() const override
Definition: vector_vertex_se2.h:274
corbo::VectorVertex::getDimension
int getDimension() const override
corbo::VectorVertex::_values
Eigen::VectorXd _values
corbo
mpc_local_planner::VectorVertexSE2
Vertex specialization for vectors in SE2.
Definition: vector_vertex_se2.h:74
vector_vertex.h
Eigen::Array< bool, -1, 1 >
mpc_local_planner::PartiallyFixedVectorVertexSE2::fixedArray
const Eigen::Array< bool, -1, 1 > fixedArray() const
Read-only access to the underlying logical array for fixed components.
Definition: vector_vertex_se2.h:327
corbo::CORBO_INF_DBL
constexpr const double CORBO_INF_DBL
mpc_local_planner::PartiallyFixedVectorVertexSE2::getNumberFiniteLowerBounds
int getNumberFiniteLowerBounds(bool unfixed_only) const override
Definition: vector_vertex_se2.h:279
mpc_local_planner::PartiallyFixedVectorVertexSE2::set
void set(const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, bool fixed=false) override
Set values and bounds at once.
Definition: vector_vertex_se2.h:209
corbo::VectorVertex::VectorVertex
VectorVertex()=default
mpc_local_planner
Definition: controller.h:44
mpc_local_planner::VectorVertexSE2::Ptr
std::shared_ptr< VectorVertexSE2 > Ptr
Definition: vector_vertex_se2.h:97
corbo::VectorVertex::_ub
Eigen::VectorXd _ub
corbo::VectorVertex::Ptr
std::shared_ptr< VectorVertex > Ptr
corbo::VectorVertex::values
Eigen::VectorXd & values()
corbo::VectorVertex::setDimension
virtual void setDimension(int dim)
mpc_local_planner::PartiallyFixedVectorVertexSE2::getDimensionUnfixed
int getDimensionUnfixed() const override
Definition: vector_vertex_se2.h:198
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
mpc_local_planner::VectorVertexSE2::UPtr
std::unique_ptr< VectorVertexSE2 > UPtr
Definition: vector_vertex_se2.h:98
corbo::VectorVertex::_lb
Eigen::VectorXd _lb
mpc_local_planner::VectorVertexSE2::VectorVertexSE2
VectorVertexSE2()=default
Default constructor.
Eigen::Map
mpc_local_planner::PartiallyFixedVectorVertexSE2::setFixed
void setFixed(int idx, bool fixed)
Set component with idx (0 <= idx < dimension()) to (un)fixed.
Definition: vector_vertex_se2.h:239
mpc_local_planner::VectorVertexSE2::set
virtual void set(const Eigen::Ref< const Eigen::VectorXd > &values, const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub, bool fixed=false)
Set values and bounds at once.
Definition: vector_vertex_se2.h:148
Eigen::Ref
mpc_local_planner::PartiallyFixedVectorVertexSE2::PartiallyFixedVectorVertexSE2
PartiallyFixedVectorVertexSE2()=default
Default constructor.
corbo::VectorVertex::setLowerBounds
void setLowerBounds(const Eigen::Ref< const Eigen::VectorXd > &lb) override
corbo::VectorVertex::UPtr
std::unique_ptr< VectorVertex > UPtr
mpc_local_planner::normalize_theta
double normalize_theta(double theta)
normalize angle to interval [-pi, pi)
Definition: math_utils.h:101
mpc_local_planner::PartiallyFixedVectorVertexSE2::isFixedComponent
bool isFixedComponent(int idx) const override
Definition: vector_vertex_se2.h:276
math_utils.h
mpc_local_planner::VectorVertexSE2::plusUnfixed
void plusUnfixed(const double *inc) override
Definition: vector_vertex_se2.h:136
mpc_local_planner::VectorVertexSE2::setData
void setData(int idx, double data) override
Definition: vector_vertex_se2.h:139
mpc_local_planner::PartiallyFixedVectorVertexSE2::_num_unfixed
int _num_unfixed
Definition: vector_vertex_se2.h:331
mpc_local_planner::PartiallyFixedVectorVertexSE2::_fixed
Eigen::Array< bool, -1, 1 > _fixed
Definition: vector_vertex_se2.h:330
corbo::VectorVertex
mpc_local_planner::VectorVertexSE2::plus
void plus(int idx, double inc) override
Definition: vector_vertex_se2.h:119
corbo::VectorVertex::setFixed
virtual void setFixed(bool fixed)
mpc_local_planner::PartiallyFixedVectorVertexSE2::setDimension
void setDimension(int dim) override
Definition: vector_vertex_se2.h:201
mpc_local_planner::PartiallyFixedVectorVertexSE2::plusUnfixed
void plusUnfixed(const double *inc) override
Definition: vector_vertex_se2.h:260


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