| Directory: | ./ |
|---|---|
| File: | include/pinocchio/algorithm/constrained-dynamics.hpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 7 | 7 | 100.0% |
| Branches: | 4 | 8 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2019-2021 INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #ifndef __pinocchio_algorithm_constrained_dynamics_hpp__ | ||
| 6 | #define __pinocchio_algorithm_constrained_dynamics_hpp__ | ||
| 7 | |||
| 8 | #include "pinocchio/algorithm/contact-info.hpp" | ||
| 9 | |||
| 10 | #include "pinocchio/algorithm/proximal.hpp" | ||
| 11 | |||
| 12 | namespace pinocchio | ||
| 13 | { | ||
| 14 | |||
| 15 | /// | ||
| 16 | /// \brief Init the forward dynamics data according to the contact information contained in | ||
| 17 | /// contact_models. | ||
| 18 | /// | ||
| 19 | /// \tparam JointCollection Collection of Joint types. | ||
| 20 | /// \tparam ConfigVectorType Type of the joint configuration vector. | ||
| 21 | /// \tparam TangentVectorType1 Type of the joint velocity vector. | ||
| 22 | /// \tparam TangentVectorType2 Type of the joint torque vector. | ||
| 23 | /// \tparam Allocator Allocator class for the std::vector. | ||
| 24 | /// | ||
| 25 | /// \param[in] model The model structure of the rigid body system. | ||
| 26 | /// \param[in] data The data structure of the rigid body system. | ||
| 27 | /// \param[in] contact_models Vector of contact information related to the problem. | ||
| 28 | /// | ||
| 29 | template< | ||
| 30 | typename Scalar, | ||
| 31 | int Options, | ||
| 32 | template<typename, int> class JointCollectionTpl, | ||
| 33 | class Allocator> | ||
| 34 | PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") | ||
| 35 | inline void initConstraintDynamics( | ||
| 36 | const ModelTpl<Scalar, Options, JointCollectionTpl> & model, | ||
| 37 | DataTpl<Scalar, Options, JointCollectionTpl> & data, | ||
| 38 | const std::vector<RigidConstraintModelTpl<Scalar, Options>, Allocator> & contact_models); | ||
| 39 | |||
| 40 | /// | ||
| 41 | /// \brief Computes the forward dynamics with contact constraints according to a given list of | ||
| 42 | /// contact information. | ||
| 43 | /// | ||
| 44 | /// \note When using forwardDynamics for the first time, you should call first | ||
| 45 | /// initConstraintDynamics to initialize the internal memory used in the algorithm. | ||
| 46 | /// | ||
| 47 | /// It computes the following problem: \[ | ||
| 48 | /// \f[ | ||
| 49 | /// \begin{eqnarray} | ||
| 50 | /// \underset{\ddot{q}}{\min} & & \| \ddot{q} - \ddot{q}_{\text{free}} \|_{M(q)} \\ | ||
| 51 | /// \text{s.t.} & & J (q) \ddot{q} + \gamma (q, \dot{q}) = 0 | ||
| 52 | /// \end{eqnarray} | ||
| 53 | /// \f] where \f$ \ddot{q}_{\text{free}} \f$ is the free acceleration (i.e. without | ||
| 54 | /// constraints), \f$ M \f$ is the mass matrix, \f$ J \f$ the constraint Jacobian and \f$ | ||
| 55 | /// \gamma \f$ is the constraint drift. | ||
| 56 | /// By default, the constraint Jacobian is assumed to be full rank, and undamped Cholesky inverse | ||
| 57 | /// is performed. | ||
| 58 | /// | ||
| 59 | /// \tparam JointCollection Collection of Joint types. | ||
| 60 | /// \tparam ConfigVectorType Type of the joint configuration vector. | ||
| 61 | /// \tparam TangentVectorType1 Type of the joint velocity vector. | ||
| 62 | /// \tparam TangentVectorType2 Type of the joint torque vector. | ||
| 63 | /// \tparam Allocator Allocator class for the std::vector. | ||
| 64 | /// | ||
| 65 | /// \param[in] model The model structure of the rigid body system. | ||
| 66 | /// \param[in] data The data structure of the rigid body system. | ||
| 67 | /// \param[in] q The joint configuration (size model.nq). | ||
| 68 | /// \param[in] v The joint velocity (size model.nv). | ||
| 69 | /// \param[in] tau The joint torque vector (size model.nv). | ||
| 70 | /// \param[in] contact_models Vector of contact models. | ||
| 71 | /// \param[in] contact_datas Vector of contact data. | ||
| 72 | /// \param[in] settings Proximal settings (mu, accuracy and maximal number of iterations). | ||
| 73 | /// | ||
| 74 | /// \note A hint: a typical value for mu is 1e-12 when two contact constraints are redundant. | ||
| 75 | /// | ||
| 76 | /// \return A reference to the joint acceleration stored in data.ddq. The Lagrange Multipliers | ||
| 77 | /// linked to the contact forces are available throw data.lambda_c vector. | ||
| 78 | /// | ||
| 79 | template< | ||
| 80 | typename Scalar, | ||
| 81 | int Options, | ||
| 82 | template<typename, int> class JointCollectionTpl, | ||
| 83 | typename ConfigVectorType, | ||
| 84 | typename TangentVectorType1, | ||
| 85 | typename TangentVectorType2, | ||
| 86 | class ConstraintModelAllocator, | ||
| 87 | class ConstraintDataAllocator> | ||
| 88 | PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") | ||
| 89 | inline const | ||
| 90 | typename DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType & constraintDynamics( | ||
| 91 | const ModelTpl<Scalar, Options, JointCollectionTpl> & model, | ||
| 92 | DataTpl<Scalar, Options, JointCollectionTpl> & data, | ||
| 93 | const Eigen::MatrixBase<ConfigVectorType> & q, | ||
| 94 | const Eigen::MatrixBase<TangentVectorType1> & v, | ||
| 95 | const Eigen::MatrixBase<TangentVectorType2> & tau, | ||
| 96 | const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintModelAllocator> & | ||
| 97 | contact_models, | ||
| 98 | std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & contact_datas, | ||
| 99 | ProximalSettingsTpl<Scalar> & settings); | ||
| 100 | |||
| 101 | /// | ||
| 102 | /// \brief Computes the forward dynamics with contact constraints according to a given list of | ||
| 103 | /// Contact information. | ||
| 104 | /// | ||
| 105 | /// \note When using forwardDynamics for the first time, you should call first | ||
| 106 | /// initConstraintDynamics to initialize the internal memory used in the algorithm. | ||
| 107 | /// | ||
| 108 | /// It computes the following problem: \f[ | ||
| 109 | /// \begin{eqnarray} | ||
| 110 | /// \underset{\ddot{q}}{\min} & & \| \ddot{q} - \ddot{q}_{\text{free}} \|_{M(q)} \\ | ||
| 111 | /// \text{s.t.} & & J (q) \ddot{q} + \gamma (q, \dot{q}) = 0 | ||
| 112 | /// \end{eqnarray} | ||
| 113 | /// \f] where \f$ \ddot{q}_{\text{free}} \f$ is the free acceleration (i.e. without | ||
| 114 | /// constraints), \f$ M \f$ is the mass matrix, \f$ J \f$ the constraint Jacobian and \f$ | ||
| 115 | /// \gamma \f$ is the constraint drift. | ||
| 116 | /// By default, the constraint Jacobian is assumed to be full rank, and undamped Cholesky inverse | ||
| 117 | /// is performed. | ||
| 118 | /// | ||
| 119 | /// \tparam JointCollection Collection of Joint types. | ||
| 120 | /// \tparam ConfigVectorType Type of the joint configuration vector. | ||
| 121 | /// \tparam TangentVectorType1 Type of the joint velocity vector. | ||
| 122 | /// \tparam TangentVectorType2 Type of the joint torque vector. | ||
| 123 | /// \tparam Allocator Allocator class for the std::vector. | ||
| 124 | /// | ||
| 125 | /// \param[in] model The model structure of the rigid body system. | ||
| 126 | /// \param[in] data The data structure of the rigid body system. | ||
| 127 | /// \param[in] q The joint configuration (size model.nq). | ||
| 128 | /// \param[in] v The joint velocity (size model.nv). | ||
| 129 | /// \param[in] tau The joint torque vector (size model.nv). | ||
| 130 | /// \param[in] contact_models Vector of contact models. | ||
| 131 | /// \param[in] contact_datas Vector of contact data. | ||
| 132 | /// | ||
| 133 | /// \return A reference to the joint acceleration stored in data.ddq. The Lagrange Multipliers | ||
| 134 | /// linked to the contact forces are available throw data.lambda_c vector. | ||
| 135 | /// | ||
| 136 | template< | ||
| 137 | typename Scalar, | ||
| 138 | int Options, | ||
| 139 | template<typename, int> class JointCollectionTpl, | ||
| 140 | typename ConfigVectorType, | ||
| 141 | typename TangentVectorType1, | ||
| 142 | typename TangentVectorType2, | ||
| 143 | class ConstraintModelAllocator, | ||
| 144 | class ConstraintDataAllocator> | ||
| 145 | PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") | ||
| 146 | inline const | ||
| 147 | 2 | typename DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType & constraintDynamics( | |
| 148 | const ModelTpl<Scalar, Options, JointCollectionTpl> & model, | ||
| 149 | DataTpl<Scalar, Options, JointCollectionTpl> & data, | ||
| 150 | const Eigen::MatrixBase<ConfigVectorType> & q, | ||
| 151 | const Eigen::MatrixBase<TangentVectorType1> & v, | ||
| 152 | const Eigen::MatrixBase<TangentVectorType2> & tau, | ||
| 153 | const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintModelAllocator> & | ||
| 154 | contact_models, | ||
| 155 | std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & contact_datas) | ||
| 156 | { | ||
| 157 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
2 | ProximalSettingsTpl<Scalar> settings; |
| 158 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
4 | return constraintDynamics(model, data, q, v, tau, contact_models, contact_datas, settings); |
| 159 | } | ||
| 160 | |||
| 161 | template< | ||
| 162 | typename Scalar, | ||
| 163 | int Options, | ||
| 164 | template<typename, int> class JointCollectionTpl, | ||
| 165 | typename ConfigVectorType, | ||
| 166 | typename TangentVectorType1, | ||
| 167 | typename TangentVectorType2, | ||
| 168 | class ModelAllocator, | ||
| 169 | class DataAllocator> | ||
| 170 | PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") | ||
| 171 | inline const | ||
| 172 | 3 | typename DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType & contactABA( | |
| 173 | const ModelTpl<Scalar, Options, JointCollectionTpl> & model, | ||
| 174 | DataTpl<Scalar, Options, JointCollectionTpl> & data, | ||
| 175 | const Eigen::MatrixBase<ConfigVectorType> & q, | ||
| 176 | const Eigen::MatrixBase<TangentVectorType1> & v, | ||
| 177 | const Eigen::MatrixBase<TangentVectorType2> & tau, | ||
| 178 | const std::vector<RigidConstraintModelTpl<Scalar, Options>, ModelAllocator> & contact_models, | ||
| 179 | std::vector<RigidConstraintDataTpl<Scalar, Options>, DataAllocator> & contact_data) | ||
| 180 | { | ||
| 181 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | ProximalSettingsTpl<Scalar> settings = ProximalSettingsTpl<Scalar>(); |
| 182 |
1/2✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
|
3 | return contactABA( |
| 183 | 9 | model, data, q.derived(), v.derived(), tau.derived(), contact_models, contact_data, settings); | |
| 184 | } | ||
| 185 | |||
| 186 | } // namespace pinocchio | ||
| 187 | |||
| 188 | #include "pinocchio/algorithm/constrained-dynamics.hxx" | ||
| 189 | |||
| 190 | #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION | ||
| 191 | #include "pinocchio/algorithm/constrained-dynamics.txx" | ||
| 192 | #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION | ||
| 193 | |||
| 194 | #endif // ifndef __pinocchio_algorithm_constrained_dynamics_hpp__ | ||
| 195 |