9#ifndef CROCODDYL_MULTIBODY_ACTIONS_CONTACT_INVDYN_HPP_
10#define CROCODDYL_MULTIBODY_ACTIONS_CONTACT_INVDYN_HPP_
12#include "crocoddyl/core/actuation-base.hpp"
13#include "crocoddyl/core/constraints/constraint-manager.hpp"
14#include "crocoddyl/core/costs/cost-sum.hpp"
15#include "crocoddyl/core/diff-action-base.hpp"
16#include "crocoddyl/multibody/contacts/multiple-contacts.hpp"
17#include "crocoddyl/multibody/data/contacts.hpp"
18#include "crocoddyl/multibody/fwd.hpp"
19#include "crocoddyl/multibody/states/multibody.hpp"
43template <
typename _Scalar>
47 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49 typedef _Scalar Scalar;
62 typedef typename MathBase::VectorXs VectorXs;
63 typedef typename MathBase::MatrixXs MatrixXs;
77 std::shared_ptr<StateMultibody> state,
78 std::shared_ptr<ActuationModelAbstract> actuation,
79 std::shared_ptr<ContactModelMultiple> contacts,
80 std::shared_ptr<CostModelSum> costs);
92 std::shared_ptr<StateMultibody> state,
93 std::shared_ptr<ActuationModelAbstract> actuation,
94 std::shared_ptr<ContactModelMultiple> contacts,
95 std::shared_ptr<CostModelSum> costs,
96 std::shared_ptr<ConstraintModelManager> constraints);
109 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
110 const Eigen::Ref<const VectorXs>& x,
111 const Eigen::Ref<const VectorXs>& u);
118 virtual void calc(
const std::shared_ptr<DifferentialActionDataAbstract>& data,
119 const Eigen::Ref<const VectorXs>& x);
135 const std::shared_ptr<DifferentialActionDataAbstract>& data,
136 const Eigen::Ref<const VectorXs>& x,
const Eigen::Ref<const VectorXs>& u);
144 const std::shared_ptr<DifferentialActionDataAbstract>& data,
145 const Eigen::Ref<const VectorXs>& x);
152 virtual std::shared_ptr<DifferentialActionDataAbstract>
createData();
159 const std::shared_ptr<DifferentialActionDataAbstract>& data);
175 const std::shared_ptr<DifferentialActionDataAbstract>& data,
176 Eigen::Ref<VectorXs> u,
const Eigen::Ref<const VectorXs>& x,
177 const std::size_t maxiter = 100,
const Scalar tol = Scalar(1e-9));
238 virtual void print(std::ostream& os)
const;
249 void init(
const std::shared_ptr<StateMultibody>& state);
250 std::shared_ptr<ActuationModelAbstract> actuation_;
251 std::shared_ptr<ContactModelMultiple> contacts_;
252 std::shared_ptr<CostModelSum> costs_;
253 std::shared_ptr<ConstraintModelManager> constraints_;
254 pinocchio::ModelTpl<Scalar>& pinocchio_;
272 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
274 typedef _Scalar Scalar;
280 typedef typename MathBase::VectorXs VectorXs;
290 const std::size_t nu,
const std::size_t nc)
291 :
Base(state, state->get_nv() - nu, state->get_nv() + nc, true, true,
304 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
305 const Eigen::Ref<const VectorXs>&,
306 const Eigen::Ref<const VectorXs>&) {
310 std::size_t nrow = 0;
311 for (std::size_t k = 0;
312 k < static_cast<std::size_t>(d->
actuation->tau_set.size()); ++k) {
324 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
325 const Eigen::Ref<const VectorXs>&) {
336 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
337 const Eigen::Ref<const VectorXs>&,
338 const Eigen::Ref<const VectorXs>&) {
341 std::size_t nrow = 0;
342 const std::size_t nv =
state_->get_nv();
343 d->dtau_dx.leftCols(nv) = d->
pinocchio->dtau_dq;
344 d->dtau_dx.rightCols(nv) = d->
pinocchio->dtau_dv;
346 d->dtau_du.leftCols(nv) = d->
pinocchio->M;
347 d->dtau_du.rightCols(nc_) = -d->
contact->Jc.transpose();
348 for (std::size_t k = 0;
349 k < static_cast<std::size_t>(d->
actuation->tau_set.size()); ++k) {
351 d->
Rx.row(nrow) = d->dtau_dx.row(k);
352 d->
Ru.row(nrow) = d->dtau_du.row(k);
363 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
364 const Eigen::Ref<const VectorXs>&) {
376 return std::allocate_shared<typename Data::ResidualDataActuation>(
377 Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
386 virtual void print(std::ostream& os)
const {
387 os <<
"ResidualModelActuation {nx=" <<
state_->get_nx()
388 <<
", ndx=" <<
state_->get_ndx() <<
", nu=" <<
nu_ <<
", na=" << na_
419 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
421 typedef _Scalar Scalar;
427 typedef typename MathBase::VectorXs VectorXs;
428 typedef typename MathBase::MatrixXs MatrixXs;
439 const pinocchio::FrameIndex
id,
const std::size_t nr,
440 const std::size_t nc)
441 :
Base(state, nr, state->get_nv() + nc, true, true, true),
453 void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
454 const Eigen::Ref<const VectorXs>&,
455 const Eigen::Ref<const VectorXs>&) {
465 virtual void calc(
const std::shared_ptr<ResidualDataAbstract>& data,
466 const Eigen::Ref<const VectorXs>&) {
477 void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
478 const Eigen::Ref<const VectorXs>&,
479 const Eigen::Ref<const VectorXs>&) {
491 virtual void calcDiff(
const std::shared_ptr<ResidualDataAbstract>& data,
492 const Eigen::Ref<const VectorXs>&) {
504 return std::allocate_shared<typename Data::ResidualDataContact>(
505 Eigen::aligned_allocator<typename Data::ResidualDataContact>(),
this,
515 virtual void print(std::ostream& os)
const {
516 os <<
"ResidualModelContact {frame=" << frame_name_ <<
", nr=" <<
nr_
526 pinocchio::FrameIndex id_;
527 std::string frame_name_;
530template <
typename _Scalar>
533 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
534 typedef _Scalar Scalar;
543 typedef typename MathBase::VectorXs VectorXs;
544 typedef typename MathBase::MatrixXs MatrixXs;
546 template <
template <
typename Scalar>
class Model>
548 Model<Scalar>*
const model)
550 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
552 &
pinocchio, model->get_actuation()->createData(),
553 std::make_shared<JointDataAbstract>(
554 model->get_state(), model->get_actuation(), model->get_nu()),
555 model->get_contacts()->createData(&
pinocchio)),
558 model->get_contacts()->get_nc()),
560 model->get_actuation()->get_nu() +
561 model->get_contacts()->get_nc()) {
563 const std::size_t nv = model->get_state()->get_nv();
564 const std::size_t nc = model->get_contacts()->get_nc_total();
565 Fu.leftCols(nv).diagonal().setOnes();
566 multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
567 MatrixXs df_dx = MatrixXs::Zero(nc, model->get_state()->get_ndx());
568 MatrixXs df_du = MatrixXs::Zero(nc, model->get_nu());
570 for (
typename ContactModelMultiple::ContactModelContainer::const_iterator
571 it = model->get_contacts()->get_contacts().begin();
572 it != model->get_contacts()->get_contacts().end(); ++it) {
573 const std::size_t nc = it->second->contact->get_nc();
574 df_du.block(fid, nv + fid, nc, nc).diagonal().setOnes();
577 model->get_contacts()->updateForceDiff(
multibody.contacts, df_dx, df_du);
580 costs->shareMemory(
this);
610 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
612 typedef _Scalar Scalar;
620 typedef typename MathBase::MatrixXs MatrixXs;
622 template <
template <
typename Scalar>
class Model>
626 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
627 dtau_du(model->get_state()->get_nv(), model->get_nu()) {
633 "Invalid argument: the shared data should be derived from "
634 "DataCollectorActMultibodyInContact");
656 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
658 typedef _Scalar Scalar;
666 template <
template <
typename Scalar>
class Model>
669 :
Base(model, data) {
674 "Invalid argument: the shared data should be derived from "
675 "DataCollectorMultibodyInContact");
677 typename ContactModelMultiple::ContactDataContainer::iterator it, end;
678 for (it = d->contacts->contacts.begin(),
679 end = d->contacts->contacts.end();
681 if (
id == it->second->frame) {
701#include <crocoddyl/multibody/actions/contact-invdyn.hxx>
Abstract class for the actuation-mapping model.
Manage the individual constraint models.
Summation of individual cost models.
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.
Abstract class for residual models.
std::shared_ptr< StateAbstract > state_
State description.
std::size_t nu_
Control dimension.
std::size_t nr_
Residual vector 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 Jc
Contact Jacobian.
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.