9 #ifndef CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
10 #define CROCODDYL_MULTIBODY_ACTIONS_FREE_INVDYN_HPP_
14 #include "crocoddyl/core/actuation-base.hpp"
15 #include "crocoddyl/core/constraints/constraint-manager.hpp"
16 #include "crocoddyl/core/costs/cost-sum.hpp"
17 #include "crocoddyl/core/diff-action-base.hpp"
18 #include "crocoddyl/core/residual-base.hpp"
19 #include "crocoddyl/core/utils/exception.hpp"
20 #include "crocoddyl/multibody/data/multibody.hpp"
21 #include "crocoddyl/multibody/fwd.hpp"
22 #include "crocoddyl/multibody/states/multibody.hpp"
41 template <
typename _Scalar>
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 typedef _Scalar Scalar;
58 typedef typename MathBase::VectorXs VectorXs;
71 std::shared_ptr<StateMultibody> state,
72 std::shared_ptr<ActuationModelAbstract> actuation,
73 std::shared_ptr<CostModelSum> costs);
84 std::shared_ptr<StateMultibody> state,
85 std::shared_ptr<ActuationModelAbstract> actuation,
86 std::shared_ptr<CostModelSum> costs,
87 std::shared_ptr<ConstraintModelManager> constraints);
100 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
101 const Eigen::Ref<const VectorXs>& x,
102 const Eigen::Ref<const VectorXs>& u);
109 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
110 const Eigen::Ref<const VectorXs>& x);
126 const std::shared_ptr<DifferentialActionDataAbstract>& data,
127 const Eigen::Ref<const VectorXs>& x,
const Eigen::Ref<const VectorXs>& u);
135 const std::shared_ptr<DifferentialActionDataAbstract>& data,
136 const Eigen::Ref<const VectorXs>& x);
143 virtual std::shared_ptr<DifferentialActionDataAbstract>
createData();
150 const std::shared_ptr<DifferentialActionDataAbstract>& data);
166 const std::shared_ptr<DifferentialActionDataAbstract>& data,
167 Eigen::Ref<VectorXs> u,
const Eigen::Ref<const VectorXs>& x,
168 const std::size_t maxiter = 100,
const Scalar tol = Scalar(1e-9));
225 virtual void print(std::ostream& os)
const;
236 void init(
const std::shared_ptr<StateMultibody>& state);
237 std::shared_ptr<ActuationModelAbstract> actuation_;
238 std::shared_ptr<CostModelSum> costs_;
239 std::shared_ptr<ConstraintModelManager> constraints_;
240 pinocchio::ModelTpl<Scalar>& pinocchio_;
257 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
259 typedef _Scalar Scalar;
266 typedef typename MathBase::VectorXs VectorXs;
267 typedef typename MathBase::MatrixXs MatrixXs;
276 const std::size_t nu)
277 :
Base(state, state->get_nv() - nu, state->get_nv(), true, true, true),
288 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
289 const Eigen::Ref<const VectorXs>&,
290 const Eigen::Ref<const VectorXs>&) {
294 std::size_t nrow = 0;
295 for (std::size_t k = 0;
296 k < static_cast<std::size_t>(d->
actuation->tau_set.size()); ++k) {
308 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
309 const Eigen::Ref<const VectorXs>&) {
320 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
321 const Eigen::Ref<const VectorXs>&,
322 const Eigen::Ref<const VectorXs>&) {
325 std::size_t nrow = 0;
326 const std::size_t nv =
state_->get_nv();
327 d->dtau_dx.leftCols(nv) = d->
pinocchio->dtau_dq;
328 d->dtau_dx.rightCols(nv) = d->
pinocchio->dtau_dv;
330 for (std::size_t k = 0;
331 k < static_cast<std::size_t>(d->
actuation->tau_set.size()); ++k) {
333 d->
Rx.row(nrow) = d->dtau_dx.row(k);
345 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
346 const Eigen::Ref<const VectorXs>&) {
358 return std::allocate_shared<typename Data::ResidualDataActuation>(
359 Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
368 virtual void print(std::ostream& os)
const {
369 os <<
"ResidualModelActuation {nx=" <<
state_->get_nx()
370 <<
", ndx=" <<
state_->get_ndx() <<
", nu=" <<
nu_ <<
", na=" <<
na_
381 template <
typename _Scalar>
384 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
385 typedef _Scalar Scalar;
393 typedef typename MathBase::VectorXs VectorXs;
395 template <
template <
typename Scalar>
class Model>
398 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
400 &
pinocchio, model->get_actuation()->createData(),
401 std::make_shared<JointDataAbstract>(
402 model->get_state(), model->get_actuation(), model->get_nu())),
406 const std::size_t nv = model->get_state()->get_nv();
407 Fu.leftCols(nv).diagonal().setOnes();
408 multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
409 costs->shareMemory(
this);
432 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
434 typedef _Scalar Scalar;
440 typedef typename MathBase::MatrixXs MatrixXs;
442 template <
template <
typename Scalar>
class Model>
446 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()) {
453 "Invalid argument: the shared data should be derived from "
454 "DataCollectorActMultibody");
477 #include <crocoddyl/multibody/actions/free-invdyn.hxx>
Abstract class for the actuation-mapping model.
Residual-based constraint.
Abstract class for differential action model.
std::shared_ptr< StateAbstract > state_
Model of the state.
VectorXs g_ub_
Lower bound of the inequality constraints.
std::size_t nu_
Control dimension.
std::size_t nh_
Number of equality constraints.
VectorXs g_lb_
Lower bound of the inequality constraints.
std::size_t ng_
Number of inequality constraints.
std::size_t na_
Dimension of the joint torques.
ResidualModelActuation(std::shared_ptr< StateMultibody > state, const std::size_t nu)
Initialize the actuation residual model.
std::shared_ptr< StateAbstract > state_
State description.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the derivatives of the actuation residual.
virtual void print(std::ostream &os) const
Print relevant information of the actuation residual model.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &, const Eigen::Ref< const VectorXs > &)
Compute the actuation residual.
virtual void calc(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
std::size_t nu_
Control dimension.
virtual std::shared_ptr< ResidualDataAbstract > createData(DataCollectorAbstract *const data)
Create the actuation residual data.
virtual void calcDiff(const std::shared_ptr< ResidualDataAbstract > &data, const Eigen::Ref< const VectorXs > &)
Differential action model for free inverse dynamics in multibody systems.
pinocchio::ModelTpl< Scalar > & get_pinocchio() const
Return the Pinocchio model.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
const std::shared_ptr< ActuationModelAbstract > & get_actuation() const
Return the actuation model.
virtual std::shared_ptr< DifferentialActionDataAbstract > createData()
Create the free inverse-dynamics data.
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 inverse-dynamics model.
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, const Eigen::Ref< const VectorXs > &u)
Compute the derivatives of the dynamics, cost and constraint functions.
DifferentialActionModelFreeInvDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< CostModelSum > costs)
Initialize the free inverse-dynamics action model.
virtual const VectorXs & get_g_lb() const
Return the lower 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)
Compute the system acceleration, cost value and constraint residuals.
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
DifferentialActionModelFreeInvDynamicsTpl(std::shared_ptr< StateMultibody > state, std::shared_ptr< ActuationModelAbstract > actuation, std::shared_ptr< CostModelSum > costs, std::shared_ptr< ConstraintModelManager > constraints)
Initialize the free inverse-dynamics action model.
virtual bool checkData(const std::shared_ptr< DifferentialActionDataAbstract > &data)
Checks that a specific data belongs to the free inverse-dynamics model.
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)
const std::shared_ptr< CostModelSum > & get_costs() const
Return the cost model.
virtual std::size_t get_ng_T() const
Return the number of equality terminal constraints.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
virtual void calc(const std::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
State multibody representation.
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 .
VectorXs xout
evolution state
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
std::shared_ptr< ActuationDataAbstract > actuation
Actuation data.
DataCollectorAbstract * shared
Shared data allocated by the action model.
VectorXs r
Residual vector.
pinocchio::DataTpl< Scalar > * pinocchio
Pinocchio data.
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
std::shared_ptr< ConstraintDataManager > constraints
Constraints data.
VectorXs tmp_xstatic
State point used for computing the quasi-static input.
DataCollectorJointActMultibody multibody
Multibody data.
pinocchio::DataTpl< Scalar > pinocchio
Pinocchio data.
std::shared_ptr< CostDataSum > costs
Costs data.
MatrixXs Ru
Jacobian of the residual vector with respect the control.
MatrixXs Rx
Jacobian of the residual vector with respect the state.
DataCollectorAbstract * shared
Shared data allocated by the action model.
VectorXs r
Residual vector.