Crocoddyl
 
Loading...
Searching...
No Matches
free-fwddyn.hpp
1
2// BSD 3-Clause License
3//
4// Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh,
5// Heriot-Watt University
6// Copyright note valid unless otherwise stated in individual files.
7// All rights reserved.
9
10#ifndef CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
11#define CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
12
13#include "crocoddyl/core/actuation-base.hpp"
14#include "crocoddyl/core/constraints/constraint-manager.hpp"
15#include "crocoddyl/core/costs/cost-sum.hpp"
16#include "crocoddyl/core/diff-action-base.hpp"
17#include "crocoddyl/multibody/data/multibody.hpp"
18#include "crocoddyl/multibody/fwd.hpp"
19#include "crocoddyl/multibody/states/multibody.hpp"
20
21namespace crocoddyl {
22
50template <typename _Scalar>
52 : public DifferentialActionModelAbstractTpl<_Scalar> {
53 public:
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55 CROCODDYL_DERIVED_CAST(DifferentialActionModelBase,
57
58 typedef _Scalar Scalar;
68 typedef typename MathBase::VectorXs VectorXs;
69 typedef typename MathBase::MatrixXs MatrixXs;
70
72 std::shared_ptr<StateMultibody> state,
73 std::shared_ptr<ActuationModelAbstract> actuation,
74 std::shared_ptr<CostModelSum> costs,
75 std::shared_ptr<ConstraintModelManager> constraints = nullptr);
77
87 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
88 const Eigen::Ref<const VectorXs>& x,
89 const Eigen::Ref<const VectorXs>& u) override;
90
96 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
97 const Eigen::Ref<const VectorXs>& x) override;
98
106 virtual void calcDiff(
107 const std::shared_ptr<DifferentialActionDataAbstract>& data,
108 const Eigen::Ref<const VectorXs>& x,
109 const Eigen::Ref<const VectorXs>& u) override;
110
116 virtual void calcDiff(
117 const std::shared_ptr<DifferentialActionDataAbstract>& data,
118 const Eigen::Ref<const VectorXs>& x) override;
119
125 virtual std::shared_ptr<DifferentialActionDataAbstract> createData() override;
126
136 template <typename NewScalar>
138
142 virtual bool checkData(
143 const std::shared_ptr<DifferentialActionDataAbstract>& data) override;
144
148 virtual void quasiStatic(
149 const std::shared_ptr<DifferentialActionDataAbstract>& data,
150 Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
151 const std::size_t maxiter = 100,
152 const Scalar tol = Scalar(1e-9)) override;
153
157 virtual std::size_t get_ng() const override;
158
162 virtual std::size_t get_nh() const override;
163
167 virtual std::size_t get_ng_T() const override;
168
172 virtual std::size_t get_nh_T() const override;
173
177 virtual const VectorXs& get_g_lb() const override;
178
182 virtual const VectorXs& get_g_ub() const override;
183
187 const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
188
192 const std::shared_ptr<CostModelSum>& get_costs() const;
193
197 const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
198
202 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
203
207 const VectorXs& get_armature() const;
208
212 void set_armature(const VectorXs& armature);
213
219 virtual void print(std::ostream& os) const override;
220
221 protected:
222 using Base::g_lb_;
223 using Base::g_ub_;
224 using Base::nu_;
225 using Base::state_;
226
227 private:
228 std::shared_ptr<ActuationModelAbstract> actuation_;
229 std::shared_ptr<CostModelSum> costs_;
230 std::shared_ptr<ConstraintModelManager> constraints_;
231 pinocchio::ModelTpl<Scalar>* pinocchio_;
232 bool without_armature_;
233 VectorXs armature_;
234};
235
236template <typename _Scalar>
238 : public DifferentialActionDataAbstractTpl<_Scalar> {
239 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
240 typedef _Scalar Scalar;
246 typedef typename MathBase::VectorXs VectorXs;
247 typedef typename MathBase::MatrixXs MatrixXs;
248
249 template <template <typename Scalar> class Model>
250 explicit DifferentialActionDataFreeFwdDynamicsTpl(Model<Scalar>* const model)
251 : Base(model),
252 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
253 multibody(
254 &pinocchio, model->get_actuation()->createData(),
255 std::make_shared<JointDataAbstract>(
256 model->get_state(), model->get_actuation(), model->get_nu())),
257 costs(model->get_costs()->createData(&multibody)),
258 Minv(model->get_state()->get_nv(), model->get_state()->get_nv()),
259 u_drift(model->get_state()->get_nv()),
260 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
261 tmp_xstatic(model->get_state()->get_nx()) {
262 multibody.joint->dtau_du.diagonal().setOnes();
263 costs->shareMemory(this);
264 if (model->get_constraints() != nullptr) {
265 constraints = model->get_constraints()->createData(&multibody);
266 constraints->shareMemory(this);
267 }
268 Minv.setZero();
269 u_drift.setZero();
270 dtau_dx.setZero();
271 tmp_xstatic.setZero();
272 }
274
275 pinocchio::DataTpl<Scalar> pinocchio;
277 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
278 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
279 MatrixXs Minv;
280 VectorXs u_drift;
281 MatrixXs dtau_dx;
282 VectorXs tmp_xstatic;
283
284 using Base::cost;
285 using Base::Fu;
286 using Base::Fx;
287 using Base::Lu;
288 using Base::Luu;
289 using Base::Lx;
290 using Base::Lxu;
291 using Base::Lxx;
292 using Base::r;
293 using Base::xout;
294};
295
296} // namespace crocoddyl
297
298/* --- Details -------------------------------------------------------------- */
299/* --- Details -------------------------------------------------------------- */
300/* --- Details -------------------------------------------------------------- */
301#include <crocoddyl/multibody/actions/free-fwddyn.hxx>
302
303CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
305CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
307
308#endif // CROCODDYL_MULTIBODY_ACTIONS_FREE_FWDDYN_HPP_
Abstract class for the actuation-mapping model.
Manage the individual constraint models.
Summation of individual cost models.
Definition cost-sum.hpp:75
Abstract class for differential action model.
std::shared_ptr< StateAbstract > state_
Model of the state.
VectorXs g_ub_
Lower bound of the inequality constraints.
VectorXs g_lb_
Lower bound of the inequality constraints.
Differential action model for free forward dynamics in multibody systems.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data) override
Check that the given data belongs to the free forward-dynamics data.
virtual const VectorXs & get_g_lb() const override
Return the lower bound of the inequality constraints.
const std::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
virtual const VectorXs & get_g_ub() const override
Return the upper bound of the inequality constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the system acceleration, and cost value.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData() override
Create the free forward-dynamics data.
virtual std::size_t get_ng() const override
Return the number of inequality constraints.
const VectorXs & get_armature() const
Return the armature vector.
virtual std::size_t get_nh_T() const override
Return the number of equality terminal constraints.
virtual std::size_t get_nh() const override
Return the number of equality constraints.
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual std::size_t get_ng_T() const override
Return the number of equality terminal constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x) override
const std::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
void set_armature(const VectorXs &armature)
Modify the armature vector.
virtual void quasiStatic(const std::shared_ptr< DifferentialActionDataAbstract > &data, Eigen::Ref< VectorXs > u, const Eigen::Ref< const VectorXs > &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9)) override
Computes the quasic static commands.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
DifferentialActionModelFreeFwdDynamicsTpl< NewScalar > cast() const
Cast the free-fwddyn model to a different scalar type.
virtual void print(std::ostream &os) const override
Print relevant information of the free forward-dynamics model.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u) override
Compute the derivatives of the contact dynamics, and cost function.
State multibody representation.
Definition multibody.hpp:34
MatrixXs Fx
Jacobian of the dynamics w.r.t. the state .
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
MatrixXs Luu
Hessian of the cost w.r.t. the control .
VectorXs Lx
Jacobian of the cost w.r.t. the state .
MatrixXs Lxx
Hessian of the cost w.r.t. the state .
VectorXs Lu
Jacobian of the cost w.r.t. the control .