generic_edge.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_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_GENERIC_EDGE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_GENERIC_EDGE_H_
27 
29 
32 
33 #include <functional>
34 
35 namespace corbo {
36 
67 template <class... VerticesT>
68 class EdgeGenericScalarFun : public Edge<VerticesT...>
69 {
70  // Use dependent names and members from the parent template class.
71  protected:
72  using Edge<VerticesT...>::_vertices;
73 
74  public:
75  using typename Edge<VerticesT...>::VertexContainer;
76  using ExtFunT = std::function<double(const VertexContainer&)>;
77  using ExtJacobT = std::function<void(const VertexContainer&, int, Eigen::Ref<Eigen::MatrixXd>, const double*)>;
78 
79  using Ptr = std::shared_ptr<EdgeGenericScalarFun>;
80  using UPtr = std::unique_ptr<EdgeGenericScalarFun>;
81 
83  EdgeGenericScalarFun(const ExtFunT& fun, bool lsq_form, VerticesT&... vertices) : Edge<VerticesT...>(vertices...), _fun(fun), _lsq_form(lsq_form)
84  {
85  }
86 
88  EdgeGenericScalarFun(const ExtFunT& fun, const ExtJacobT& jacobian, bool lsq_form, VerticesT&... vertices)
89  : Edge<VerticesT...>(vertices...), _fun(fun), _jacob(jacobian), _lsq_form(lsq_form)
90  {
91  }
92 
93  int getDimension() const override { return 1; }
94 
95  // implements interface method
96  bool isLinear() const override { return false; }
97  // implements interface method
98  bool isLeastSquaresForm() const override { return _lsq_form; }
99  // implements interface method
100  bool providesJacobian() const override { return (bool)_jacob; }
101 
102  // implements interface method
103  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override { values[0] = _fun(_vertices); }
104  // implements interface method
105  void computeJacobian(int vtx_idx, Eigen::Ref<Eigen::MatrixXd> block_jacobian, const double* multiplier = nullptr) override
106  {
107  if (_jacob)
108  _jacob(_vertices, vtx_idx, block_jacobian, multiplier);
109  else
110  BaseEdge::computeJacobian(vtx_idx, block_jacobian, multiplier);
111  }
112 
113  // implements interface method
114  void setLinear(bool linear) { _linear = linear; }
115 
116  protected:
117  ExtFunT _fun;
119  bool _lsq_form;
120  bool _linear = false;
121 
122  public:
124 };
125 
149 template <int D, class... VerticesT>
150 class EdgeGenericVectorFun : public Edge<VerticesT...>
151 {
152  // Use dependent names and members from the parent template class.
153  public:
154  using typename Edge<VerticesT...>::VertexContainer;
155 
156  using Ptr = std::shared_ptr<EdgeGenericVectorFun>;
157  using UPtr = std::unique_ptr<EdgeGenericVectorFun>;
158 
159  protected:
160  using Edge<VerticesT...>::_vertices;
161 
162  public:
164  using ExtFunT = std::function<void(const VertexContainer&, Eigen::Ref<ErrorVector>)>;
165  using ExtJacobT = std::function<void(const VertexContainer&, int, Eigen::Ref<Eigen::MatrixXd>, const double*)>;
166 
168  EdgeGenericVectorFun(const ExtFunT& fun, bool lsq_form, VerticesT&... vertices) : Edge<VerticesT...>(vertices...), _fun(fun), _lsq_form(lsq_form)
169  {
170  }
171 
173  EdgeGenericVectorFun(const ExtFunT& fun, const ExtJacobT& jacobian, bool lsq_form, VerticesT&... vertices)
174  : Edge<VerticesT...>(vertices...), _fun(fun), _jacob(jacobian), _lsq_form(lsq_form)
175  {
176  }
177 
178  int getDimension() const override { return D; }
179  // implements interface method
180  bool isLinear() const override { return false; }
181  // implements interface method
182  bool isLeastSquaresForm() const override { return _lsq_form; }
183  // implements interface method
184  bool providesJacobian() const override { return (bool)_jacob; }
185 
186  // implements interface method
187  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override { _fun(_vertices, values); }
188  // implements interface method
189  void computeJacobian(int vtx_idx, Eigen::Ref<Eigen::MatrixXd> block_jacobian, const double* multiplier) override
190  {
191  if (_jacob)
192  _jacob(_vertices, vtx_idx, block_jacobian, multiplier);
193  else
194  BaseEdge::computeJacobian(vtx_idx, block_jacobian, multiplier);
195  }
196 
197  // implements interface method
198  void setLinear(bool linear) { _linear = linear; }
199 
200  protected:
201  ExtFunT _fun;
203  bool _lsq_form;
204  bool _linear = false;
205 
206  public:
208 };
209 
210 template <class... VerticesT>
211 class MixedEdgeGenericVectorFun : public MixedEdge<VerticesT...>
212 {
213  // Use dependent names and members from the parent template class.
214  public:
215  using typename MixedEdge<VerticesT...>::VertexContainer;
216 
217  using Ptr = std::shared_ptr<MixedEdgeGenericVectorFun>;
218  using UPtr = std::unique_ptr<MixedEdgeGenericVectorFun>;
219 
220  protected:
221  using MixedEdge<VerticesT...>::_vertices;
222 
223  public:
224  using ExtPrecomputeT = std::function<void(const VertexContainer&)>;
225  using ExtFunT = std::function<void(const VertexContainer&, Eigen::Ref<Eigen::VectorXd>)>;
226  // using ExtJacobT = std::function<void(const VertexContainer&, int, Eigen::Ref<Eigen::MatrixXd>, const double*)>;
227 
229  MixedEdgeGenericVectorFun(int obj_dim, int eq_dim, int ineq_dim, const ExtPrecomputeT& precompute_fun, const ExtFunT& obj_fun,
230  const ExtFunT& eq_fun, const ExtFunT& ineq_fun, VerticesT&... vertices)
231  : MixedEdge<VerticesT...>(vertices...),
232  _preqcompute_fun(precompute_fun),
233  _obj_fun(obj_fun),
234  _eq_fun(eq_fun),
235  _ineq_fun(ineq_fun),
236  _obj_dim(obj_dim),
237  _eq_dim(eq_dim),
238  _ineq_dim(ineq_dim)
239  {
240  }
241 
243  // MixedEdgeGenericVectorFun(const ExtFunT& fun, const ExtJacobT& jacobian, bool lsq_form, VerticesT&... vertices)
244  //: Edge<VerticesT...>(vertices...), _fun(fun), _jacob(jacobian), _lsq_form(lsq_form)
245  //{
246  //}
247 
248  int getObjectiveDimension() const override { return _obj_dim; }
249  int getEqualityDimension() const override { return _eq_dim; }
250  int getInequalityDimension() const override { return _ineq_dim; }
251 
252  // implements interface method
253  // bool isLinear() const override { return false; }
254  // implements interface method
255  bool isObjectiveLeastSquaresForm() const override { return _obj_lsq_form; }
256  // implements interface method
257  // bool providesJacobian() const override { return (bool)_jacob; }
258 
259  // implements interface method
260  void precompute() override { _preqcompute_fun(_vertices); }
261  void computeObjectiveValues(Eigen::Ref<Eigen::VectorXd> obj_values) override { _obj_fun(_vertices, obj_values); }
262  void computeEqualityValues(Eigen::Ref<Eigen::VectorXd> eq_values) override { _eq_fun(_vertices, eq_values); }
263  void computeInequalityValues(Eigen::Ref<Eigen::VectorXd> ineq_values) override { _ineq_fun(_vertices, ineq_values); }
264  // implements interface method
265  // void computeJacobian(int vtx_idx, Eigen::Ref<Eigen::MatrixXd> block_jacobian, const double* multiplier) override
266  //{
267  // if (_jacob)
268  // _jacob(_vertices, vtx_idx, block_jacobian, multiplier);
269  // else
270  // BaseEdge::computeJacobian(vtx_idx, block_jacobian, multiplier);
271  //}
272 
273  // implements interface method
274  void setLinear(bool linear) { _linear = linear; }
275 
276  void setObjectiveLsqForm(bool obj_lsq) { _obj_lsq_form = obj_lsq; }
277 
278  protected:
280  ExtFunT _obj_fun;
283  // ExtJacobT _obj_jacob;
284  bool _obj_lsq_form = false;
285  bool _linear = false;
286  int _obj_dim = 0;
287  int _eq_dim = 0;
288  int _ineq_dim = 0;
289 
290  public:
292 };
293 
294 template <typename T, void (T::*ComputeMethod)(int, const Eigen::Ref<const Eigen::VectorXd>&, Eigen::Ref<Eigen::VectorXd>) const>
295 class UnaryVectorVertexEdge : public Edge<VectorVertex>
296 {
297  public:
298  using Ptr = std::shared_ptr<UnaryVectorVertexEdge>;
299 
300  explicit UnaryVectorVertexEdge(int dim, int k, const T& fun_obj, VectorVertex& vertex, bool is_linear = false, bool is_lsq = false)
301  : Edge<VectorVertex>(vertex), _dimension(dim), _k(k), _is_linear(is_linear), _is_lsq(is_lsq), _fun_obj(fun_obj)
302  {
303  }
304 
305  int getDimension() const override { return _dimension; }
306 
307  // implements interface method
308  bool isLinear() const override { return _is_linear; }
309 
310  // implements interface method
311  bool isLeastSquaresForm() const override { return _is_lsq; }
312 
313  // implements interface method
314  bool providesJacobian() const override { return false; }
315 
316  // implements interface method
318  {
319  const VectorVertex* vertex = static_cast<const VectorVertex*>(_vertices[0]);
320  (_fun_obj.*ComputeMethod)(_k, vertex->values(), values);
321  }
322 
323  private:
324  int _dimension = 0;
325  int _k = 0;
326  bool _is_linear = false;
327  bool _is_lsq = false;
328 
329  const T& _fun_obj;
330 };
331 
332 template <typename T, void (T::*ComputeMethod)(int, double, Eigen::Ref<Eigen::VectorXd>) const>
333 class UnaryScalarVertexEdge : public Edge<ScalarVertex>
334 {
335  public:
336  using Ptr = std::shared_ptr<UnaryScalarVertexEdge>;
337 
338  explicit UnaryScalarVertexEdge(int dim, int k, const T& fun_obj, ScalarVertex& vertex, bool is_linear, bool is_lsq)
339  : Edge<ScalarVertex>(vertex), _dimension(dim), _k(k), _is_linear(is_linear), _is_lsq(is_lsq), _fun_obj(fun_obj)
340  {
341  }
342 
343  int getDimension() const override { return _dimension; }
344 
345  // implements interface method
346  bool isLinear() const override { return _is_linear; }
347 
348  // implements interface method
349  bool isLeastSquaresForm() const override { return _is_lsq; }
350 
351  // implements interface method
352  bool providesJacobian() const override { return false; }
353 
354  // implements interface method
356  {
357  const ScalarVertex* vertex = static_cast<const ScalarVertex*>(_vertices[0]);
358  (_fun_obj.*ComputeMethod)(_k, vertex->value(), values);
359  }
360 
361  private:
362  int _dimension = 0;
363  int _k = 0;
364  bool _is_linear = false;
365  bool _is_lsq = false;
366 
367  const T& _fun_obj;
368 };
369 
370 template <typename T, void (T::*ComputeMethod)(int, const Eigen::Ref<const Eigen::VectorXd>&, const Eigen::Ref<const Eigen::VectorXd>&,
371  Eigen::Ref<Eigen::VectorXd>) const>
372 class BinaryVectorVertexEdge : public Edge<VectorVertex, VectorVertex>
373 {
374  public:
375  using Ptr = std::shared_ptr<BinaryVectorVertexEdge>;
376 
377  explicit BinaryVectorVertexEdge(int dim, int k, const T& fun_obj, VectorVertex& vertex1, VectorVertex& vertex2, bool is_linear, bool is_lsq)
378  : Edge<VectorVertex, VectorVertex>(vertex1, vertex2), _dimension(dim), _k(k), _is_linear(is_linear), _is_lsq(is_lsq), _fun_obj(fun_obj)
379  {
380  }
381 
382  int getDimension() const override { return _dimension; }
383 
384  // implements interface method
385  bool isLinear() const override { return _is_linear; }
386 
387  // implements interface method
388  bool isLeastSquaresForm() const override { return _is_lsq; }
389 
390  // implements interface method
391  bool providesJacobian() const override { return false; }
392 
393  // implements interface method
395  {
396  const VectorVertex* vertex1 = static_cast<const VectorVertex*>(_vertices[0]);
397  const VectorVertex* vertex2 = static_cast<const VectorVertex*>(_vertices[1]);
398  (_fun_obj.*ComputeMethod)(_k, vertex1->values(), vertex2->values(), values);
399  }
400 
401  private:
402  int _dimension = 0;
403  int _k = 0;
404  bool _is_linear = false;
405  bool _is_lsq = false;
406 
407  const T& _fun_obj;
408 };
409 
410 template <typename T, void (T::*ComputeMethod)(int, const Eigen::Ref<const Eigen::VectorXd>&, double, Eigen::Ref<Eigen::VectorXd>) const>
411 class BinaryVectorScalarVertexEdge : public Edge<VectorVertex, ScalarVertex>
412 {
413  public:
414  using Ptr = std::shared_ptr<BinaryVectorScalarVertexEdge>;
415 
416  explicit BinaryVectorScalarVertexEdge(int dim, int k, const T& fun_obj, VectorVertex& vertex1, ScalarVertex& vertex2, bool is_linear, bool is_lsq)
417  : Edge<VectorVertex, ScalarVertex>(vertex1, vertex2), _dimension(dim), _k(k), _is_linear(is_linear), _is_lsq(is_lsq), _fun_obj(fun_obj)
418  {
419  }
420 
421  int getDimension() const override { return _dimension; }
422 
423  // implements interface method
424  bool isLinear() const override { return _is_linear; }
425 
426  // implements interface method
427  bool isLeastSquaresForm() const override { return _is_lsq; }
428 
429  // implements interface method
430  bool providesJacobian() const override { return false; }
431 
432  // implements interface method
434  {
435  const VectorVertex* vertex1 = static_cast<const VectorVertex*>(_vertices[0]);
436  const ScalarVertex* vertex2 = static_cast<const ScalarVertex*>(_vertices[1]);
437  (_fun_obj.*ComputeMethod)(_k, vertex1->values(), vertex2->value(), values);
438  }
439 
440  private:
441  int _dimension = 0;
442  int _k = 0;
443  bool _is_linear = false;
444  bool _is_lsq = false;
445 
446  const T& _fun_obj;
447 };
448 
449 template <typename T, void (T::*ComputeMethod)(int, const Eigen::Ref<const Eigen::VectorXd>&, const Eigen::Ref<const Eigen::VectorXd>&, double,
450  Eigen::Ref<Eigen::VectorXd>) const>
451 class TernaryVectorScalarVertexEdge : public Edge<VectorVertex, VectorVertex, ScalarVertex>
452 {
453  public:
454  using Ptr = std::shared_ptr<TernaryVectorScalarVertexEdge>;
455 
456  explicit TernaryVectorScalarVertexEdge(int dim, int k, const T& fun_obj, VectorVertex& vec_vtx1, VectorVertex& vec_vtx2, ScalarVertex& scalar_vtx,
457  bool is_linear, bool is_lsq)
458  : Edge<VectorVertex, VectorVertex, ScalarVertex>(vec_vtx1, vec_vtx2, scalar_vtx),
459  _dimension(dim),
460  _k(k),
461  _is_linear(is_linear),
462  _is_lsq(is_lsq),
463  _fun_obj(fun_obj)
464  {
465  }
466 
467  int getDimension() const override { return _dimension; }
468 
469  // implements interface method
470  bool isLinear() const override { return _is_linear; }
471 
472  // implements interface method
473  bool isLeastSquaresForm() const override { return _is_lsq; }
474 
475  // implements interface method
476  bool providesJacobian() const override { return false; }
477 
478  // implements interface method
479  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override
480  {
481  const VectorVertex* vec_vtx1 = static_cast<const VectorVertex*>(_vertices[0]);
482  const VectorVertex* vec_vtx2 = static_cast<const VectorVertex*>(_vertices[1]);
483  const ScalarVertex* scalar_vtx = static_cast<const ScalarVertex*>(_vertices[2]);
484  (_fun_obj.*ComputeMethod)(_k, vec_vtx1->values(), vec_vtx2->values(), scalar_vtx->value(), values);
485  }
486 
487  private:
488  int _dimension = 0;
489  int _k = 0;
490  bool _is_linear = false;
491  bool _is_lsq = false;
492 
493  const T& _fun_obj;
494 };
495 
496 } // namespace corbo
497 
498 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_GENERIC_EDGE_H_
corbo::UnaryScalarVertexEdge::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:374
corbo::EdgeInterface::Ptr
std::shared_ptr< EdgeInterface > Ptr
Definition: edge_interface.h:81
corbo::EdgeGenericVectorFun::setLinear
void setLinear(bool linear)
Definition: generic_edge.h:220
corbo::MixedEdgeGenericVectorFun::setLinear
void setLinear(bool linear)
Definition: generic_edge.h:296
corbo::UnaryScalarVertexEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:368
corbo::MixedEdgeGenericVectorFun::MixedEdgeGenericVectorFun
MixedEdgeGenericVectorFun(int obj_dim, int eq_dim, int ineq_dim, const ExtPrecomputeT &precompute_fun, const ExtFunT &obj_fun, const ExtFunT &eq_fun, const ExtFunT &ineq_fun, VerticesT &... vertices)
Construct generic vector function edge by passing the dimension D, the function object and all vertic...
Definition: generic_edge.h:251
corbo::BinaryVectorVertexEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:416
corbo::UnaryScalarVertexEdge::UnaryScalarVertexEdge
UnaryScalarVertexEdge(int dim, int k, const T &fun_obj, ScalarVertex &vertex, bool is_linear, bool is_lsq)
Definition: generic_edge.h:360
corbo::MixedEdgeGenericVectorFun::computeObjectiveValues
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override
Definition: generic_edge.h:283
corbo::UnaryScalarVertexEdge::_dimension
int _dimension
Definition: generic_edge.h:384
corbo::Edge< VerticesT... >::VertexContainer
std::array< VertexInterface *, numVerticesCompileTime > VertexContainer
Typedef to represent the vertex container.
Definition: edge.h:203
corbo::EdgeGenericScalarFun::_jacob
ExtJacobT _jacob
Definition: generic_edge.h:162
corbo::EdgeGenericScalarFun::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:137
corbo::TernaryVectorScalarVertexEdge::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:498
corbo::UnaryVectorVertexEdge::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:336
corbo::MixedEdgeGenericVectorFun::isObjectiveLeastSquaresForm
bool isObjectiveLeastSquaresForm() const override
Definition: generic_edge.h:277
corbo::EdgeGenericScalarFun::setLinear
void setLinear(bool linear)
Definition: generic_edge.h:158
corbo::EdgeGenericScalarFun::Ptr
std::shared_ptr< EdgeGenericScalarFun > Ptr
Definition: generic_edge.h:123
corbo::MixedEdgeGenericVectorFun::_obj_lsq_form
bool _obj_lsq_form
Definition: generic_edge.h:306
corbo::EdgeGenericVectorFun::EdgeGenericVectorFun
EdgeGenericVectorFun(const ExtFunT &fun, bool lsq_form, VerticesT &... vertices)
Construct generic vector function edge by passing the dimension D, the function object and all vertic...
Definition: generic_edge.h:190
corbo::MixedEdgeGenericVectorFun::precompute
void precompute() override
Definition: generic_edge.h:282
corbo::BinaryVectorVertexEdge::_is_lsq
bool _is_lsq
Definition: generic_edge.h:427
corbo::EdgeGenericVectorFun::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:206
corbo::MixedEdgeGenericVectorFun::_eq_fun
ExtFunT _eq_fun
Definition: generic_edge.h:303
corbo::BinaryVectorScalarVertexEdge::_is_lsq
bool _is_lsq
Definition: generic_edge.h:466
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::EdgeGenericVectorFun::computeJacobian
void computeJacobian(int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multiplier) override
Compute edge block jacobian for a given vertex.
Definition: generic_edge.h:211
corbo::MixedEdge< VerticesT... >::VertexContainer
std::array< VertexInterface *, numVerticesCompileTime > VertexContainer
Typedef to represent the vertex container.
Definition: edge.h:321
corbo::EdgeGenericScalarFun::ExtJacobT
std::function< void(const VertexContainer &, int, Eigen::Ref< Eigen::MatrixXd >, const double *)> ExtJacobT
Definition: generic_edge.h:121
corbo::Edge< VerticesT... >::Edge
Edge()=delete
corbo::BinaryVectorVertexEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:407
corbo::UnaryVectorVertexEdge::_is_lsq
bool _is_lsq
Definition: generic_edge.h:349
corbo::UnaryScalarVertexEdge
Definition: generic_edge.h:355
corbo::UnaryVectorVertexEdge::_k
int _k
Definition: generic_edge.h:347
corbo::EdgeGenericVectorFun::ErrorVector
Eigen::Matrix< double, D, 1 > ErrorVector
Definition: generic_edge.h:185
scalar_vertex.h
corbo::BinaryVectorScalarVertexEdge::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:452
corbo::MixedEdgeGenericVectorFun::setObjectiveLsqForm
void setObjectiveLsqForm(bool obj_lsq)
Definition: generic_edge.h:298
corbo::BinaryVectorScalarVertexEdge::_is_linear
bool _is_linear
Definition: generic_edge.h:465
corbo::EdgeGenericVectorFun::_linear
bool _linear
Definition: generic_edge.h:226
corbo::BinaryVectorScalarVertexEdge::BinaryVectorScalarVertexEdge
BinaryVectorScalarVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vertex1, ScalarVertex &vertex2, bool is_linear, bool is_lsq)
Definition: generic_edge.h:438
vector_vertex.h
corbo::TernaryVectorScalarVertexEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:501
corbo::MixedEdge< VerticesT... >::_vertices
const VertexContainer _vertices
Vertex container.
Definition: edge.h:383
corbo::MixedEdgeGenericVectorFun::_obj_dim
int _obj_dim
Definition: generic_edge.h:308
corbo::UnaryVectorVertexEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:330
corbo::EdgeGenericVectorFun::_fun
ExtFunT _fun
Store the external function or functor.
Definition: generic_edge.h:223
corbo::TernaryVectorScalarVertexEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:495
corbo::MixedEdgeGenericVectorFun::ExtFunT
std::function< void(const VertexContainer &, Eigen::Ref< Eigen::VectorXd >)> ExtFunT
Definition: generic_edge.h:247
corbo::MixedEdgeGenericVectorFun::_eq_dim
int _eq_dim
Definition: generic_edge.h:309
corbo::EdgeGenericVectorFun::_lsq_form
bool _lsq_form
Definition: generic_edge.h:225
corbo::MixedEdgeGenericVectorFun::_ineq_fun
ExtFunT _ineq_fun
Definition: generic_edge.h:304
corbo::VectorVertex::values
const Eigen::VectorXd & values() const
Read-access to the underlying value vector.
Definition: vector_vertex.h:284
corbo::BinaryVectorVertexEdge
Definition: generic_edge.h:394
corbo::EdgeGenericScalarFun::_fun
ExtFunT _fun
Store the external function or functor.
Definition: generic_edge.h:161
corbo::BinaryVectorVertexEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:410
corbo::TernaryVectorScalarVertexEdge
Definition: generic_edge.h:473
corbo::EdgeGenericScalarFun::ExtFunT
std::function< double(const VertexContainer &)> ExtFunT
Definition: generic_edge.h:120
corbo::EdgeGenericScalarFun::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:147
corbo::TernaryVectorScalarVertexEdge::_is_linear
bool _is_linear
Definition: generic_edge.h:512
corbo::MixedEdgeGenericVectorFun::_obj_fun
ExtFunT _obj_fun
Store the external function or functor.
Definition: generic_edge.h:302
corbo::UnaryVectorVertexEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:327
corbo::EdgeGenericScalarFun::_lsq_form
bool _lsq_form
Definition: generic_edge.h:163
corbo::BinaryVectorVertexEdge::_fun_obj
const T & _fun_obj
Definition: generic_edge.h:429
corbo::MixedEdge
Definition: edge.h:310
corbo::EdgeGenericVectorFun::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:200
corbo::MixedEdgeGenericVectorFun::computeEqualityValues
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override
Definition: generic_edge.h:284
corbo::EdgeGenericVectorFun::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:209
corbo::UnaryVectorVertexEdge::UnaryVectorVertexEdge
UnaryVectorVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vertex, bool is_linear=false, bool is_lsq=false)
Definition: generic_edge.h:322
corbo::UnaryScalarVertexEdge::_fun_obj
const T & _fun_obj
Definition: generic_edge.h:389
corbo::BinaryVectorVertexEdge::BinaryVectorVertexEdge
BinaryVectorVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vertex1, VectorVertex &vertex2, bool is_linear, bool is_lsq)
Definition: generic_edge.h:399
corbo::UnaryScalarVertexEdge::_is_lsq
bool _is_lsq
Definition: generic_edge.h:387
edge.h
corbo::EdgeGenericVectorFun::ExtFunT
std::function< void(const VertexContainer &, Eigen::Ref< ErrorVector >)> ExtFunT
Definition: generic_edge.h:186
corbo::EdgeGenericScalarFun::EdgeGenericScalarFun
EdgeGenericScalarFun(const ExtFunT &fun, bool lsq_form, VerticesT &... vertices)
Construct generic scalar function edge by passing the function object and all vertices.
Definition: generic_edge.h:127
corbo::MixedEdgeGenericVectorFun
Definition: generic_edge.h:233
corbo::TernaryVectorScalarVertexEdge::_dimension
int _dimension
Definition: generic_edge.h:510
corbo::EdgeGenericVectorFun
Generic edge for functions .
Definition: generic_edge.h:172
corbo::EdgeGenericScalarFun::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:142
corbo::UnaryVectorVertexEdge::_fun_obj
const T & _fun_obj
Definition: generic_edge.h:351
corbo::BinaryVectorVertexEdge::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:413
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:690
corbo::UnaryScalarVertexEdge::_is_linear
bool _is_linear
Definition: generic_edge.h:386
corbo::EdgeGenericScalarFun::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:140
corbo::TernaryVectorScalarVertexEdge::_fun_obj
const T & _fun_obj
Definition: generic_edge.h:515
corbo::BinaryVectorVertexEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:404
corbo::BinaryVectorScalarVertexEdge::_k
int _k
Definition: generic_edge.h:464
corbo::MixedEdgeGenericVectorFun::_ineq_dim
int _ineq_dim
Definition: generic_edge.h:310
corbo::EdgeGenericScalarFun::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: generic_edge.h:144
corbo::BinaryVectorScalarVertexEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:443
corbo::UnaryScalarVertexEdge::_k
int _k
Definition: generic_edge.h:385
corbo::EdgeGenericScalarFun::computeJacobian
void computeJacobian(int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multiplier=nullptr) override
Compute edge block jacobian for a given vertex.
Definition: generic_edge.h:149
corbo::UnaryVectorVertexEdge
Definition: generic_edge.h:317
corbo::EdgeInterface::UPtr
std::unique_ptr< EdgeInterface > UPtr
Definition: edge_interface.h:82
corbo::UnaryVectorVertexEdge::_is_linear
bool _is_linear
Definition: generic_edge.h:348
corbo::UnaryScalarVertexEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:371
corbo::EdgeGenericVectorFun::ExtJacobT
std::function< void(const VertexContainer &, int, Eigen::Ref< Eigen::MatrixXd >, const double *)> ExtJacobT
Definition: generic_edge.h:187
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::TernaryVectorScalarVertexEdge::TernaryVectorScalarVertexEdge
TernaryVectorScalarVertexEdge(int dim, int k, const T &fun_obj, VectorVertex &vec_vtx1, VectorVertex &vec_vtx2, ScalarVertex &scalar_vtx, bool is_linear, bool is_lsq)
Definition: generic_edge.h:478
corbo::ScalarVertex::value
const double & value() const
Get underlying value.
Definition: scalar_vertex.h:225
corbo::BinaryVectorVertexEdge::_k
int _k
Definition: generic_edge.h:425
corbo::BaseEdge::computeJacobian
virtual void computeJacobian(int vtx_idx, Eigen::Ref< Eigen::MatrixXd > block_jacobian, const double *multipliers=nullptr)
Compute edge block jacobian for a given vertex.
Definition: edge_interface.cpp:77
corbo::BinaryVectorVertexEdge::_is_linear
bool _is_linear
Definition: generic_edge.h:426
corbo::TernaryVectorScalarVertexEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:492
corbo::BinaryVectorScalarVertexEdge::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:446
corbo::TernaryVectorScalarVertexEdge::_is_lsq
bool _is_lsq
Definition: generic_edge.h:513
corbo::BinaryVectorVertexEdge::_dimension
int _dimension
Definition: generic_edge.h:424
corbo::BinaryVectorScalarVertexEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:455
corbo::BinaryVectorScalarVertexEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:449
corbo::ScalarVertex
Vertex implementation for scalar values.
Definition: scalar_vertex.h:72
corbo::UnaryVectorVertexEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:339
corbo::MixedEdgeGenericVectorFun::ExtPrecomputeT
std::function< void(const VertexContainer &)> ExtPrecomputeT
Definition: generic_edge.h:246
corbo::EdgeGenericVectorFun::_jacob
ExtJacobT _jacob
Definition: generic_edge.h:224
corbo::MixedEdgeGenericVectorFun::_preqcompute_fun
ExtPrecomputeT _preqcompute_fun
Definition: generic_edge.h:301
corbo::MixedEdgeGenericVectorFun::computeInequalityValues
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override
Definition: generic_edge.h:285
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
corbo::BinaryVectorScalarVertexEdge
Definition: generic_edge.h:433
corbo::EdgeGenericScalarFun::_linear
bool _linear
Definition: generic_edge.h:164
corbo::UnaryVectorVertexEdge::_dimension
int _dimension
Definition: generic_edge.h:346
corbo::Edge
Templated base edge class that stores an arbitary number of value.
Definition: edge.h:170
corbo::MixedEdgeGenericVectorFun::getObjectiveDimension
int getObjectiveDimension() const override
Construct generic vector function edge by passing the dimension D, the function object,...
Definition: generic_edge.h:270
corbo::UnaryVectorVertexEdge::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:333
corbo::MixedEdgeGenericVectorFun::getEqualityDimension
int getEqualityDimension() const override
Definition: generic_edge.h:271
corbo::TernaryVectorScalarVertexEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:489
corbo::BinaryVectorScalarVertexEdge::_fun_obj
const T & _fun_obj
Definition: generic_edge.h:468
corbo::EdgeGenericVectorFun::isLinear
bool isLinear() const override
Return true if the edge is linear (and hence its Hessian is always zero)
Definition: generic_edge.h:202
corbo::MixedEdgeGenericVectorFun::getInequalityDimension
int getInequalityDimension() const override
Definition: generic_edge.h:272
corbo::VectorVertex
Vertex implementation that stores an Eigen::VectorXd (dynamic dimension)
Definition: vector_vertex.h:73
corbo::EdgeGenericVectorFun::isLeastSquaresForm
bool isLeastSquaresForm() const override
Defines if the edge is formulated as Least-Squares form.
Definition: generic_edge.h:204
corbo::BinaryVectorScalarVertexEdge::_dimension
int _dimension
Definition: generic_edge.h:463
corbo::TernaryVectorScalarVertexEdge::_k
int _k
Definition: generic_edge.h:511
corbo::UnaryScalarVertexEdge::getDimension
int getDimension() const override
Get dimension of the edge (dimension of the cost-function/constraint value vector)
Definition: generic_edge.h:365
corbo::EdgeGenericScalarFun::UPtr
std::unique_ptr< EdgeGenericScalarFun > UPtr
Definition: generic_edge.h:124
corbo::UnaryScalarVertexEdge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override
Compute function values.
Definition: generic_edge.h:377
corbo::MixedEdgeGenericVectorFun::_linear
bool _linear
Definition: generic_edge.h:307
corbo::Edge< VerticesT... >::_vertices
const VertexContainer _vertices
Vertex container.
Definition: edge.h:258


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