Crocoddyl
 
Loading...
Searching...
No Matches
contact-fwddyn.hpp
1
2// BSD 3-Clause License
3//
4// Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh, CTU, INRIA,
5// University of Oxford, Heriot-Watt University
6// Copyright note valid unless otherwise stated in individual files.
7// All rights reserved.
9
10#ifndef CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_
11#define CROCODDYL_MULTIBODY_ACTIONS_CONTACT_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/contacts/multiple-contacts.hpp"
18#include "crocoddyl/multibody/data/contacts.hpp"
19#include "crocoddyl/multibody/fwd.hpp"
20#include "crocoddyl/multibody/states/multibody.hpp"
21
22namespace crocoddyl {
23
71template <typename _Scalar>
73 : public DifferentialActionModelAbstractTpl<_Scalar> {
74 public:
75 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76 CROCODDYL_DERIVED_CAST(DifferentialActionModelBase,
78
79 typedef _Scalar Scalar;
90 typedef typename MathBase::VectorXs VectorXs;
91 typedef typename MathBase::MatrixXs MatrixXs;
92
110 std::shared_ptr<StateMultibody> state,
111 std::shared_ptr<ActuationModelAbstract> actuation,
112 std::shared_ptr<ContactModelMultiple> contacts,
113 std::shared_ptr<CostModelSum> costs,
114 const Scalar JMinvJt_damping = Scalar(0.),
115 const bool enable_force = false);
116
135 std::shared_ptr<StateMultibody> state,
136 std::shared_ptr<ActuationModelAbstract> actuation,
137 std::shared_ptr<ContactModelMultiple> contacts,
138 std::shared_ptr<CostModelSum> costs,
139 std::shared_ptr<ConstraintModelManager> constraints,
140 const Scalar JMinvJt_damping = Scalar(0.),
141 const bool enable_force = false);
143
153 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
154 const Eigen::Ref<const VectorXs>& x,
155 const Eigen::Ref<const VectorXs>& u) override;
156
169 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
170 const Eigen::Ref<const VectorXs>& x) override;
171
179 virtual void calcDiff(
180 const std::shared_ptr<DifferentialActionDataAbstract>& data,
181 const Eigen::Ref<const VectorXs>& x,
182 const Eigen::Ref<const VectorXs>& u) override;
183
195 virtual void calcDiff(
196 const std::shared_ptr<DifferentialActionDataAbstract>& data,
197 const Eigen::Ref<const VectorXs>& x) override;
198
204 virtual std::shared_ptr<DifferentialActionDataAbstract> createData() override;
205
215 template <typename NewScalar>
217
222 virtual bool checkData(
223 const std::shared_ptr<DifferentialActionDataAbstract>& data) override;
224
228 virtual void quasiStatic(
229 const std::shared_ptr<DifferentialActionDataAbstract>& data,
230 Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
231 const std::size_t maxiter = 100,
232 const Scalar tol = Scalar(1e-9)) override;
233
237 virtual std::size_t get_ng() const override;
238
242 virtual std::size_t get_nh() const override;
243
247 virtual std::size_t get_ng_T() const override;
248
252 virtual std::size_t get_nh_T() const override;
253
257 virtual const VectorXs& get_g_lb() const override;
258
262 virtual const VectorXs& get_g_ub() const override;
263
267 const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
268
272 const std::shared_ptr<ContactModelMultiple>& get_contacts() const;
273
277 const std::shared_ptr<CostModelSum>& get_costs() const;
278
282 const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
283
287 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
288
292 const VectorXs& get_armature() const;
293
297 const Scalar get_damping_factor() const;
298
302 void set_armature(const VectorXs& armature);
303
307 void set_damping_factor(const Scalar damping);
308
314 virtual void print(std::ostream& os) const override;
315
316 protected:
317 using Base::g_lb_;
318 using Base::g_ub_;
319 using Base::nu_;
320 using Base::state_;
321
322 private:
323 void init();
324 std::shared_ptr<ActuationModelAbstract> actuation_;
325 std::shared_ptr<ContactModelMultiple> contacts_;
326 std::shared_ptr<CostModelSum> costs_;
327 std::shared_ptr<ConstraintModelManager> constraints_;
328 pinocchio::ModelTpl<Scalar>* pinocchio_;
329 bool with_armature_;
330 VectorXs armature_;
331 Scalar JMinvJt_damping_;
333 bool enable_force_;
335};
336
337template <typename _Scalar>
339 : public DifferentialActionDataAbstractTpl<_Scalar> {
340 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
341 typedef _Scalar Scalar;
347 typedef typename MathBase::VectorXs VectorXs;
348 typedef typename MathBase::MatrixXs MatrixXs;
349
350 template <template <typename Scalar> class Model>
352 Model<Scalar>* const model)
353 : Base(model),
354 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
355 multibody(
356 &pinocchio, model->get_actuation()->createData(),
357 std::make_shared<JointDataAbstract>(
358 model->get_state(), model->get_actuation(), model->get_nu()),
359 model->get_contacts()->createData(&pinocchio)),
360 costs(model->get_costs()->createData(&multibody)),
361 Kinv(model->get_state()->get_nv() +
362 model->get_contacts()->get_nc_total(),
363 model->get_state()->get_nv() +
364 model->get_contacts()->get_nc_total()),
365 df_dx(model->get_contacts()->get_nc_total(),
366 model->get_state()->get_ndx()),
367 df_du(model->get_contacts()->get_nc_total(), model->get_nu()),
368 tmp_xstatic(model->get_state()->get_nx()),
369 tmp_Jstatic(model->get_state()->get_nv(),
370 model->get_nu() + model->get_contacts()->get_nc_total()) {
371 multibody.joint->dtau_du.diagonal().setOnes();
372 costs->shareMemory(this);
373 if (model->get_constraints() != nullptr) {
374 constraints = model->get_constraints()->createData(&multibody);
375 constraints->shareMemory(this);
376 }
377 Kinv.setZero();
378 df_dx.setZero();
379 df_du.setZero();
380 tmp_xstatic.setZero();
381 tmp_Jstatic.setZero();
382 pinocchio.lambda_c.resize(model->get_contacts()->get_nc_total());
383 pinocchio.lambda_c.setZero();
384 }
386
387 pinocchio::DataTpl<Scalar> pinocchio;
389 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
390 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
391 MatrixXs Kinv;
392 MatrixXs df_dx;
393 MatrixXs df_du;
394 VectorXs tmp_xstatic;
395 MatrixXs tmp_Jstatic;
396
397 using Base::cost;
398 using Base::Fu;
399 using Base::Fx;
400 using Base::Lu;
401 using Base::Luu;
402 using Base::Lx;
403 using Base::Lxu;
404 using Base::Lxx;
405 using Base::r;
406 using Base::xout;
407};
408
409} // namespace crocoddyl
410
411/* --- Details -------------------------------------------------------------- */
412/* --- Details -------------------------------------------------------------- */
413/* --- Details -------------------------------------------------------------- */
414#include <crocoddyl/multibody/actions/contact-fwddyn.hxx>
415
416CROCODDYL_DECLARE_EXTERN_TEMPLATE_CLASS(
418CROCODDYL_DECLARE_EXTERN_TEMPLATE_STRUCT(
420
421#endif // CROCODDYL_MULTIBODY_ACTIONS_CONTACT_FWDDYN_HPP_
Abstract class for the actuation-mapping model.
Manage the individual constraint models.
Define a stack of contact 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 contact forward dynamics in multibody systems.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data) override
Check that the given data belongs to the contact 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
Compute the derivatives of the cost functions with respect to the state only.
virtual const VectorXs & get_g_ub() const override
Return the upper bound of the inequality constraints.
DifferentialActionModelContactFwdDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< ContactModelMultiple > contacts, std::shared_ptr< CostModelSum > costs, const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the contact forward-dynamics action model.
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 contact 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.
DifferentialActionModelContactFwdDynamicsTpl< NewScalar > cast() const
Cast the contact-fwddyn model to a different scalar type.
void set_damping_factor(const Scalar damping)
Modify the damping factor used in operational space inertia matrix.
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
Compute the total cost value for nodes that depends only on the state.
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.
const Scalar get_damping_factor() const
Return the damping factor used in operational space inertia matrix.
const std::shared_ptr< ContactModelMultiple > & get_contacts() const
Return the contact model.
DifferentialActionModelContactFwdDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< ContactModelMultiple > contacts, std::shared_ptr< CostModelSum > costs, std::shared_ptr< ConstraintModelManager > constraints, const Scalar JMinvJt_damping=Scalar(0.), const bool enable_force=false)
Initialize the contact forward-dynamics action model.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
virtual void print(std::ostream &os) const override
Print relevant information of the contact 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 .