Crocoddyl
 
Loading...
Searching...
No Matches
free-fwddyn.hpp
1
2// BSD 3-Clause License
3//
4// Copyright (C) 2019-2024, 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 <stdexcept>
14
15#ifdef PINOCCHIO_WITH_CPPAD_SUPPORT // TODO(cmastalli): Removed after merging
16 // Pinocchio v.2.4.8
17#include <pinocchio/codegen/cppadcg.hpp>
18#endif
19
20#include "crocoddyl/core/actuation-base.hpp"
21#include "crocoddyl/core/constraints/constraint-manager.hpp"
22#include "crocoddyl/core/costs/cost-sum.hpp"
23#include "crocoddyl/core/diff-action-base.hpp"
24#include "crocoddyl/core/utils/exception.hpp"
25#include "crocoddyl/multibody/data/multibody.hpp"
26#include "crocoddyl/multibody/fwd.hpp"
27#include "crocoddyl/multibody/states/multibody.hpp"
28
29namespace crocoddyl {
30
58template <typename _Scalar>
60 : public DifferentialActionModelAbstractTpl<_Scalar> {
61 public:
62 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63
64 typedef _Scalar Scalar;
74 typedef typename MathBase::VectorXs VectorXs;
75 typedef typename MathBase::MatrixXs MatrixXs;
76
78 std::shared_ptr<StateMultibody> state,
79 std::shared_ptr<ActuationModelAbstract> actuation,
80 std::shared_ptr<CostModelSum> costs,
81 std::shared_ptr<ConstraintModelManager> constraints = nullptr);
83
93 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
94 const Eigen::Ref<const VectorXs>& x,
95 const Eigen::Ref<const VectorXs>& u);
96
102 virtual void calc(const std::shared_ptr<DifferentialActionDataAbstract>& data,
103 const Eigen::Ref<const VectorXs>& x);
104
112 virtual void calcDiff(
113 const std::shared_ptr<DifferentialActionDataAbstract>& data,
114 const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>& u);
115
121 virtual void calcDiff(
122 const std::shared_ptr<DifferentialActionDataAbstract>& data,
123 const Eigen::Ref<const VectorXs>& x);
124
130 virtual std::shared_ptr<DifferentialActionDataAbstract> createData();
131
135 virtual bool checkData(
136 const std::shared_ptr<DifferentialActionDataAbstract>& data);
137
141 virtual void quasiStatic(
142 const std::shared_ptr<DifferentialActionDataAbstract>& data,
143 Eigen::Ref<VectorXs> u, const Eigen::Ref<const VectorXs>& x,
144 const std::size_t maxiter = 100, const Scalar tol = Scalar(1e-9));
145
149 virtual std::size_t get_ng() const;
150
154 virtual std::size_t get_nh() const;
155
159 virtual std::size_t get_ng_T() const;
160
164 virtual std::size_t get_nh_T() const;
165
169 virtual const VectorXs& get_g_lb() const;
170
174 virtual const VectorXs& get_g_ub() const;
175
179 const std::shared_ptr<ActuationModelAbstract>& get_actuation() const;
180
184 const std::shared_ptr<CostModelSum>& get_costs() const;
185
189 const std::shared_ptr<ConstraintModelManager>& get_constraints() const;
190
194 pinocchio::ModelTpl<Scalar>& get_pinocchio() const;
195
199 const VectorXs& get_armature() const;
200
204 void set_armature(const VectorXs& armature);
205
211 virtual void print(std::ostream& os) const;
212
213 protected:
214 using Base::g_lb_;
215 using Base::g_ub_;
216 using Base::nu_;
217 using Base::state_;
218
219 private:
220 std::shared_ptr<ActuationModelAbstract> actuation_;
221 std::shared_ptr<CostModelSum> costs_;
222 std::shared_ptr<ConstraintModelManager> constraints_;
223 pinocchio::ModelTpl<Scalar>& pinocchio_;
224 bool without_armature_;
225 VectorXs armature_;
226};
227
228template <typename _Scalar>
230 : public DifferentialActionDataAbstractTpl<_Scalar> {
231 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
232 typedef _Scalar Scalar;
238 typedef typename MathBase::VectorXs VectorXs;
239 typedef typename MathBase::MatrixXs MatrixXs;
240
241 template <template <typename Scalar> class Model>
242 explicit DifferentialActionDataFreeFwdDynamicsTpl(Model<Scalar>* const model)
243 : Base(model),
244 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
245 multibody(
246 &pinocchio, model->get_actuation()->createData(),
247 std::make_shared<JointDataAbstract>(
248 model->get_state(), model->get_actuation(), model->get_nu())),
249 costs(model->get_costs()->createData(&multibody)),
250 Minv(model->get_state()->get_nv(), model->get_state()->get_nv()),
251 u_drift(model->get_state()->get_nv()),
252 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
253 tmp_xstatic(model->get_state()->get_nx()) {
254 multibody.joint->dtau_du.diagonal().setOnes();
255 costs->shareMemory(this);
256 if (model->get_constraints() != nullptr) {
257 constraints = model->get_constraints()->createData(&multibody);
258 constraints->shareMemory(this);
259 }
260 Minv.setZero();
261 u_drift.setZero();
262 dtau_dx.setZero();
263 tmp_xstatic.setZero();
264 }
265
266 pinocchio::DataTpl<Scalar> pinocchio;
268 std::shared_ptr<CostDataSumTpl<Scalar> > costs;
269 std::shared_ptr<ConstraintDataManagerTpl<Scalar> > constraints;
270 MatrixXs Minv;
271 VectorXs u_drift;
272 MatrixXs dtau_dx;
273 VectorXs tmp_xstatic;
274
275 using Base::cost;
276 using Base::Fu;
277 using Base::Fx;
278 using Base::Lu;
279 using Base::Luu;
280 using Base::Lx;
281 using Base::Lxu;
282 using Base::Lxx;
283 using Base::r;
284 using Base::xout;
285};
286
287} // namespace crocoddyl
288
289/* --- Details -------------------------------------------------------------- */
290/* --- Details -------------------------------------------------------------- */
291/* --- Details -------------------------------------------------------------- */
292#include <crocoddyl/multibody/actions/free-fwddyn.hxx>
293
294#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:73
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.
const std::shared_ptr< ConstraintModelManager > & get_constraints() const
Return the constraint model manager.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
virtual std::size_t get_nh() const
Return the number of equality constraints.
virtual void print(std::ostream &os) const
Print relevant information of the free forward-dynamics model.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the contact dynamics, and cost function.
const VectorXs & get_armature() const
Return the armature vector.
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData()
Create the free forward-dynamics data.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
Compute the system acceleration, and cost value.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data)
Check that the given data belongs to the free forward-dynamics data.
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))
Computes the quasic static commands.
virtual void calcDiff(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
virtual std::size_t get_ng_T() const
Return the number of equality terminal constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
State multibody representation.
Definition multibody.hpp:35
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 .