aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
centroidal-acceleration.hpp
Go to the documentation of this file.
1#pragma once
2
5
6namespace aligator {
7
8template <typename Scalar> struct CentroidalAccelerationDataTpl;
9
21template <typename _Scalar>
23
24public:
25 using Scalar = _Scalar;
27 using Base = StageFunctionTpl<Scalar>;
28 using BaseData = typename Base::Data;
29 using Data = CentroidalAccelerationDataTpl<Scalar>;
30 using ContactMap = ContactMapTpl<Scalar>;
31
32 CentroidalAccelerationResidualTpl(const int ndx, const int nu,
33 const double mass, const Vector3s &gravity,
34 const ContactMap &contact_map,
35 const int force_size)
36 : Base(ndx, nu, 3), contact_map_(contact_map),
37 nk_(size_t(nu) / size_t(force_size)), mass_(mass), gravity_(gravity),
38 force_size_(force_size) {
39 if (contact_map.getSize() != nk_) {
41 fmt::format("Contact ids and nk should be the same: now "
42 "({} and {}).",
43 contact_map.getSize(), nk_));
44 }
45 }
46
47 void evaluate(const ConstVectorRef &, const ConstVectorRef &u,
48 const ConstVectorRef &, BaseData &data) const;
49
50 void computeJacobians(const ConstVectorRef &, const ConstVectorRef &,
51 const ConstVectorRef &, BaseData &data) const;
52
53 shared_ptr<BaseData> createData() const {
54 return allocate_shared_eigen_aligned<Data>(this);
55 }
56
58
59protected:
60 size_t nk_;
61 double mass_;
62 Vector3s gravity_;
64};
65
66template <typename Scalar>
68 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
69 using Base = StageFunctionDataTpl<Scalar>;
70
72 const CentroidalAccelerationResidualTpl<Scalar> *model);
73};
74
75} // namespace aligator
76
77#include "aligator/modelling/centroidal/centroidal-acceleration.hxx"
78
79#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
80#include "./centroidal-acceleration.txx"
81#endif
#define ALIGATOR_DOMAIN_ERROR(msg)
Base definitions for ternary functions.
Main package namespace.
CentroidalAccelerationDataTpl(const CentroidalAccelerationResidualTpl< Scalar > *model)
This residual returns the linear acceleration of a centroidal model with state , computed from the ex...
CentroidalAccelerationDataTpl< Scalar > Data
CentroidalAccelerationResidualTpl(const int ndx, const int nu, const double mass, const Vector3s &gravity, const ContactMap &contact_map, const int force_size)
void evaluate(const ConstVectorRef &, const ConstVectorRef &u, const ConstVectorRef &, BaseData &data) const
shared_ptr< BaseData > createData() const
Instantiate a Data object.
void computeJacobians(const ConstVectorRef &, const ConstVectorRef &, const ConstVectorRef &, BaseData &data) const
Base struct for function data.
Class representing ternary functions .
const int nu
Control dimension.
StageFunctionDataTpl< Scalar > Data