aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
multibody-wrench-cone.hpp
Go to the documentation of this file.
1#pragma once
2
3#include "./fwd.hpp"
5
6#include <pinocchio/multibody/model.hpp>
7#ifdef ALIGATOR_PINOCCHIO_V3
8#include <pinocchio/algorithm/proximal.hpp>
9
10namespace aligator {
11
12template <typename Scalar> struct MultibodyWrenchConeDataTpl;
13
19template <typename _Scalar>
20struct MultibodyWrenchConeResidualTpl : StageFunctionTpl<_Scalar> {
21public:
22 using Scalar = _Scalar;
24 using Base = StageFunctionTpl<Scalar>;
25 using BaseData = typename Base::Data;
26 using Model = pinocchio::ModelTpl<Scalar>;
27 using SE3 = pinocchio::SE3Tpl<Scalar>;
28 using Data = MultibodyWrenchConeDataTpl<Scalar>;
29 using RigidConstraintModelVector = PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(
30 pinocchio::RigidConstraintModel);
31 using RigidConstraintDataVector =
32 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintData);
33 using ProxSettings = pinocchio::ProximalSettingsTpl<Scalar>;
34
35 Model pin_model_;
36 MatrixXs actuation_matrix_;
37 RigidConstraintModelVector constraint_models_;
38 ProxSettings prox_settings_;
39 double mu_;
40 double hL_;
41 double hW_;
42 int contact_id_;
43
44 Eigen::Matrix<Scalar, 17, 6> Acone_;
45
46 MultibodyWrenchConeResidualTpl(
47 const int ndx, const Model &model, const MatrixXs &actuation,
48 const RigidConstraintModelVector &constraint_models,
49 const ProxSettings &prox_settings, const std::string &contact_name,
50 const double mu, const double half_length, const double half_width)
51 : Base(ndx, (int)actuation.cols(), 17), pin_model_(model),
52 actuation_matrix_(actuation), constraint_models_(constraint_models),
53 prox_settings_(prox_settings), mu_(mu), hL_(half_length),
54 hW_(half_width) {
55 if (model.nv != actuation.rows()) {
57 fmt::format("actuation matrix should have number of rows = pinocchio "
58 "model nv ({} and {}).",
59 actuation.rows(), model.nv));
60 }
61 contact_id_ = -1;
62 for (std::size_t i = 0; i < constraint_models.size(); i++) {
63 if (constraint_models[i].name == contact_name) {
64 contact_id_ = (int)i;
65 }
66 }
67 if (contact_id_ == -1) {
69 "Contact name is not included in constraint models");
70 }
71 Acone_ << 0, 0, -1, 0, 0, 0, -1, 0, -mu_, 0, 0, 0, 1, 0, -mu_, 0, 0, 0, 0,
72 -1, -mu_, 0, 0, 0, 0, 1, -mu_, 0, 0, 0, 0, 0, -hW_, -1, 0, 0, 0, 0,
73 -hW_, 1, 0, 0, 0, 0, -hL_, 0, -1, 0, 0, 0, -hL_, 0, 1, 0, -hW_, -hL_,
74 -(hL_ + hW_) * mu_, mu_, mu_, -1, -hW_, hL_, -(hL_ + hW_) * mu_, mu_,
75 -mu_, -1, hW_, -hL_, -(hL_ + hW_) * mu_, -mu_, mu_, -1, hW_, hL_,
76 -(hL_ + hW_) * mu_, -mu_, -mu_, -1, hW_, hL_, -(hL_ + hW_) * mu_, mu_,
77 mu_, 1, hW_, -hL_, -(hL_ + hW_) * mu_, mu_, -mu_, 1, -hW_, hL_,
78 -(hL_ + hW_) * mu_, -mu_, mu_, 1, -hW_, -hL_, -(hL_ + hW_) * mu_, -mu_,
79 -mu_, 1;
80 }
81
82 void evaluate(const ConstVectorRef &x, const ConstVectorRef &u,
83 BaseData &data) const;
84
85 void computeJacobians(const ConstVectorRef &, const ConstVectorRef &,
86 BaseData &data) const;
87
88 shared_ptr<BaseData> createData() const {
89 return std::make_shared<Data>(this);
90 }
91};
92
93template <typename Scalar>
94struct MultibodyWrenchConeDataTpl : StageFunctionDataTpl<Scalar> {
95 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
96 using Base = StageFunctionDataTpl<Scalar>;
97 using PinData = pinocchio::DataTpl<Scalar>;
98 using VectorXs = typename math_types<Scalar>::VectorXs;
99 using MatrixXs = typename math_types<Scalar>::MatrixXs;
100 using Matrix6Xs = typename math_types<Scalar>::Matrix6Xs;
101 using RigidConstraintDataVector =
102 PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintData);
103
105 PinData pin_data_;
106 VectorXs tau_;
107 Matrix6Xs temp_;
108
109 RigidConstraintDataVector constraint_datas_;
110 pinocchio::ProximalSettingsTpl<Scalar> settings;
111
112 MultibodyWrenchConeDataTpl(
113 const MultibodyWrenchConeResidualTpl<Scalar> *model);
114};
115
116} // namespace aligator
117
118#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
119#include "aligator/modelling/multibody/multibody-wrench-cone.txx"
120#endif
121
122#endif // ALIGATOR_PINOCCHIO_V3
#define ALIGATOR_RUNTIME_ERROR(...)
Definition exceptions.hpp:7
#define ALIGATOR_DOMAIN_ERROR(msg)
Base definitions for ternary functions.
#define ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
Definition math.hpp:8
pinocchio::DataTpl< Scalar, Options > PinData
Definition context.hpp:10
Main package namespace.