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"
43 template <
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 boost::shared_ptr<StateMultibody> state,
78 boost::shared_ptr<ActuationModelAbstract> actuation,
79 boost::shared_ptr<ContactModelMultiple> contacts,
80 boost::shared_ptr<CostModelSum> costs);
92 boost::shared_ptr<StateMultibody> state,
93 boost::shared_ptr<ActuationModelAbstract> actuation,
94 boost::shared_ptr<ContactModelMultiple> contacts,
95 boost::shared_ptr<CostModelSum> costs,
96 boost::shared_ptr<ConstraintModelManager> constraints);
110 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
111 const Eigen::Ref<const VectorXs>& x,
const Eigen::Ref<const VectorXs>& u);
119 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
120 const Eigen::Ref<const VectorXs>& x);
136 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
137 const Eigen::Ref<const VectorXs>& x,
const Eigen::Ref<const VectorXs>& u);
145 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
146 const Eigen::Ref<const VectorXs>& x);
153 virtual boost::shared_ptr<DifferentialActionDataAbstract>
createData();
160 const boost::shared_ptr<DifferentialActionDataAbstract>& data);
176 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
177 Eigen::Ref<VectorXs> u,
const Eigen::Ref<const VectorXs>& x,
178 const std::size_t maxiter = 100,
const Scalar tol = Scalar(1e-9));
223 const boost::shared_ptr<CostModelSum>&
get_costs()
const;
239 virtual void print(std::ostream& os)
const;
250 void init(
const boost::shared_ptr<StateMultibody>& state);
251 boost::shared_ptr<ActuationModelAbstract> actuation_;
252 boost::shared_ptr<ContactModelMultiple> contacts_;
253 boost::shared_ptr<CostModelSum> costs_;
254 boost::shared_ptr<ConstraintModelManager> constraints_;
255 pinocchio::ModelTpl<Scalar>& pinocchio_;
273 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
275 typedef _Scalar Scalar;
281 typedef typename MathBase::VectorXs VectorXs;
291 const std::size_t nu,
const std::size_t nc)
292 :
Base(state, state->get_nv() - nu, state->get_nv() + nc, true, true,
305 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
306 const Eigen::Ref<const VectorXs>&,
307 const Eigen::Ref<const VectorXs>&) {
311 std::size_t nrow = 0;
312 for (std::size_t k = 0;
313 k < static_cast<std::size_t>(d->
actuation->tau_set.size()); ++k) {
325 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
326 const Eigen::Ref<const VectorXs>&) {
337 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
338 const Eigen::Ref<const VectorXs>&,
339 const Eigen::Ref<const VectorXs>&) {
342 std::size_t nrow = 0;
343 const std::size_t nv =
state_->get_nv();
344 d->dtau_dx.leftCols(nv) = d->
pinocchio->dtau_dq;
345 d->dtau_dx.rightCols(nv) = d->
pinocchio->dtau_dv;
347 d->dtau_du.leftCols(nv) = d->
pinocchio->M;
348 d->dtau_du.rightCols(nc_) = -d->
contact->Jc.transpose();
349 for (std::size_t k = 0;
350 k < static_cast<std::size_t>(d->
actuation->tau_set.size()); ++k) {
352 d->
Rx.row(nrow) = d->dtau_dx.row(k);
353 d->
Ru.row(nrow) = d->dtau_du.row(k);
364 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
365 const Eigen::Ref<const VectorXs>&) {
377 return boost::allocate_shared<typename Data::ResidualDataActuation>(
378 Eigen::aligned_allocator<typename Data::ResidualDataActuation>(),
387 virtual void print(std::ostream& os)
const {
388 os <<
"ResidualModelActuation {nx=" <<
state_->get_nx()
389 <<
", ndx=" <<
state_->get_ndx() <<
", nu=" <<
nu_ <<
", na=" << na_
420 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
422 typedef _Scalar Scalar;
428 typedef typename MathBase::VectorXs VectorXs;
429 typedef typename MathBase::MatrixXs MatrixXs;
440 const pinocchio::FrameIndex
id,
const std::size_t nr,
441 const std::size_t nc)
442 :
Base(state, nr, state->get_nv() + nc, true, true, true),
454 void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
455 const Eigen::Ref<const VectorXs>&,
456 const Eigen::Ref<const VectorXs>&) {
466 virtual void calc(
const boost::shared_ptr<ResidualDataAbstract>& data,
467 const Eigen::Ref<const VectorXs>&) {
478 void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
479 const Eigen::Ref<const VectorXs>&,
480 const Eigen::Ref<const VectorXs>&) {
492 virtual void calcDiff(
const boost::shared_ptr<ResidualDataAbstract>& data,
493 const Eigen::Ref<const VectorXs>&) {
505 return boost::allocate_shared<typename Data::ResidualDataContact>(
506 Eigen::aligned_allocator<typename Data::ResidualDataContact>(),
this,
516 virtual void print(std::ostream& os)
const {
517 os <<
"ResidualModelContact {frame=" << frame_name_ <<
", nr=" <<
nr_
527 pinocchio::FrameIndex id_;
528 std::string frame_name_;
531 template <
typename _Scalar>
534 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
535 typedef _Scalar Scalar;
544 typedef typename MathBase::VectorXs VectorXs;
545 typedef typename MathBase::MatrixXs MatrixXs;
547 template <
template <
typename Scalar>
class Model>
549 Model<Scalar>*
const model)
551 pinocchio(pinocchio::DataTpl<Scalar>(model->get_pinocchio())),
553 &
pinocchio, model->get_actuation()->createData(),
554 boost::make_shared<JointDataAbstract>(
555 model->get_state(), model->get_actuation(), model->get_nu()),
556 model->get_contacts()->createData(&
pinocchio)),
559 model->get_contacts()->get_nc()),
561 model->get_actuation()->get_nu() +
562 model->get_contacts()->get_nc()) {
564 const std::size_t nv = model->get_state()->get_nv();
565 const std::size_t nc = model->get_contacts()->get_nc_total();
566 Fu.leftCols(nv).diagonal().setOnes();
567 multibody.joint->da_du.leftCols(nv).diagonal().setOnes();
568 MatrixXs df_dx = MatrixXs::Zero(nc, model->get_state()->get_ndx());
569 MatrixXs df_du = MatrixXs::Zero(nc, model->get_nu());
571 for (
typename ContactModelMultiple::ContactModelContainer::const_iterator
572 it = model->get_contacts()->get_contacts().begin();
573 it != model->get_contacts()->get_contacts().end(); ++it) {
574 const std::size_t nc = it->second->contact->get_nc();
575 df_du.block(fid, nv + fid, nc, nc).diagonal().setOnes();
578 model->get_contacts()->updateForceDiff(
multibody.contacts, df_dx, df_du);
581 costs->shareMemory(
this);
591 boost::shared_ptr<CostDataSum>
costs;
611 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
613 typedef _Scalar Scalar;
621 typedef typename MathBase::MatrixXs MatrixXs;
623 template <
template <
typename Scalar>
class Model>
627 dtau_dx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
628 dtau_du(model->get_state()->get_nv(), model->get_nu()) {
634 "Invalid argument: the shared data should be derived from "
635 "DataCollectorActMultibodyInContact");
647 boost::shared_ptr<ContactDataMultiple>
contact;
657 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
659 typedef _Scalar Scalar;
667 template <
template <
typename Scalar>
class Model>
670 :
Base(model, data) {
675 "Invalid argument: the shared data should be derived from "
676 "DataCollectorMultibodyInContact");
678 typename ContactModelMultiple::ContactDataContainer::iterator it, end;
679 for (it = d->contacts->contacts.begin(),
680 end = d->contacts->contacts.end();
682 if (
id == it->second->frame) {
702 #include <crocoddyl/multibody/actions/contact-invdyn.hxx>
Abstract class for the actuation-mapping model.
Abstract class for differential action model.
VectorXs g_ub_
Lower bound of the inequality constraints.
boost::shared_ptr< StateAbstract > state_
Model of the state.
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.
boost::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 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.