Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2021-2025, LAAS-CNRS, University of Edinburgh, |
5 |
|
|
// Heriot-Watt University |
6 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
7 |
|
|
// All rights reserved. |
8 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
9 |
|
|
|
10 |
|
|
namespace crocoddyl { |
11 |
|
|
|
12 |
|
|
template <typename Scalar> |
13 |
|
✗ |
ResidualModelImpulseCoMTpl<Scalar>::ResidualModelImpulseCoMTpl( |
14 |
|
|
std::shared_ptr<StateMultibody> state) |
15 |
|
|
: Base(state, 3, 0, true, true, false), |
16 |
|
✗ |
pin_model_(state->get_pinocchio()) {} |
17 |
|
|
|
18 |
|
|
template <typename Scalar> |
19 |
|
✗ |
void ResidualModelImpulseCoMTpl<Scalar>::calc( |
20 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data, |
21 |
|
|
const Eigen::Ref<const VectorXs>& x, const Eigen::Ref<const VectorXs>&) { |
22 |
|
|
// Compute the residual residual give the reference CoM position |
23 |
|
✗ |
Data* d = static_cast<Data*>(data.get()); |
24 |
|
✗ |
const std::size_t nq = state_->get_nq(); |
25 |
|
✗ |
const std::size_t nv = state_->get_nv(); |
26 |
|
|
const Eigen::VectorBlock<const Eigen::Ref<const VectorXs>, Eigen::Dynamic> q = |
27 |
|
✗ |
x.head(nq); |
28 |
|
|
const Eigen::VectorBlock<const Eigen::Ref<const VectorXs>, Eigen::Dynamic> v = |
29 |
|
✗ |
x.tail(nv); |
30 |
|
|
|
31 |
|
✗ |
pinocchio::centerOfMass(*pin_model_.get(), d->pinocchio_internal, q, |
32 |
|
✗ |
d->impulses->vnext - v); |
33 |
|
✗ |
data->r = d->pinocchio_internal.vcom[0]; |
34 |
|
|
} |
35 |
|
|
|
36 |
|
|
template <typename Scalar> |
37 |
|
✗ |
void ResidualModelImpulseCoMTpl<Scalar>::calcDiff( |
38 |
|
|
const std::shared_ptr<ResidualDataAbstract>& data, |
39 |
|
|
const Eigen::Ref<const VectorXs>&, const Eigen::Ref<const VectorXs>&) { |
40 |
|
✗ |
Data* d = static_cast<Data*>(data.get()); |
41 |
|
|
|
42 |
|
|
// Compute the derivatives of the frame placement |
43 |
|
✗ |
const std::size_t nv = state_->get_nv(); |
44 |
|
✗ |
const std::size_t ndx = state_->get_ndx(); |
45 |
|
✗ |
pinocchio::getCenterOfMassVelocityDerivatives( |
46 |
|
✗ |
*pin_model_.get(), d->pinocchio_internal, d->dvc_dq); |
47 |
|
✗ |
pinocchio::jacobianCenterOfMass(*pin_model_.get(), d->pinocchio_internal, |
48 |
|
|
false); |
49 |
|
✗ |
d->ddv_dv = d->impulses->dvnext_dx.rightCols(ndx - nv); |
50 |
|
✗ |
d->ddv_dv.diagonal().array() -= Scalar(1); |
51 |
|
✗ |
data->Rx.leftCols(nv) = d->dvc_dq; |
52 |
|
✗ |
data->Rx.leftCols(nv).noalias() += |
53 |
|
✗ |
d->pinocchio_internal.Jcom * d->impulses->dvnext_dx.leftCols(nv); |
54 |
|
✗ |
data->Rx.rightCols(ndx - nv).noalias() = |
55 |
|
✗ |
d->pinocchio_internal.Jcom * d->ddv_dv; |
56 |
|
|
} |
57 |
|
|
|
58 |
|
|
template <typename Scalar> |
59 |
|
|
std::shared_ptr<ResidualDataAbstractTpl<Scalar> > |
60 |
|
✗ |
ResidualModelImpulseCoMTpl<Scalar>::createData( |
61 |
|
|
DataCollectorAbstract* const data) { |
62 |
|
✗ |
return std::allocate_shared<Data>(Eigen::aligned_allocator<Data>(), this, |
63 |
|
✗ |
data); |
64 |
|
|
} |
65 |
|
|
|
66 |
|
|
template <typename Scalar> |
67 |
|
|
template <typename NewScalar> |
68 |
|
✗ |
ResidualModelImpulseCoMTpl<NewScalar> ResidualModelImpulseCoMTpl<Scalar>::cast() |
69 |
|
|
const { |
70 |
|
|
typedef ResidualModelImpulseCoMTpl<NewScalar> ReturnType; |
71 |
|
|
typedef StateMultibodyTpl<NewScalar> StateType; |
72 |
|
✗ |
ReturnType ret( |
73 |
|
✗ |
std::static_pointer_cast<StateType>(state_->template cast<NewScalar>())); |
74 |
|
✗ |
return ret; |
75 |
|
|
} |
76 |
|
|
|
77 |
|
|
template <typename Scalar> |
78 |
|
✗ |
void ResidualModelImpulseCoMTpl<Scalar>::print(std::ostream& os) const { |
79 |
|
✗ |
os << "ResidualModelImpulseCoM"; |
80 |
|
|
} |
81 |
|
|
|
82 |
|
|
} // namespace crocoddyl |
83 |
|
|
|