18 #ifndef __se3_aba_derivatives_hxx__ 19 #define __se3_aba_derivatives_hxx__ 21 #include "pinocchio/multibody/visitor.hpp" 22 #include "pinocchio/algorithm/check.hpp" 23 #include "pinocchio/algorithm/aba.hpp" 24 #include "pinocchio/algorithm/rnea-derivatives.hxx" 30 typedef boost::fusion::vector<
33 const Eigen::VectorXd &,
34 const Eigen::VectorXd &
39 template<
typename Jo
intModel>
42 const se3::Model & model,
44 const Eigen::VectorXd & q,
45 const Eigen::VectorXd & v)
47 const Model::JointIndex & i = jmodel.id();
48 const Model::JointIndex & parent = model.
parents[i];
51 jmodel.calc(jdata.derived(),q,v);
54 data.
v[i] = jdata.v();
59 data.
v[i] += data.
liMi[i].actInv(data.
v[parent]);
64 ov = data.
oMi[i].act(data.
v[i]);
65 data.
a[i] = jdata.c() + (data.
v[i] ^ jdata.v());
69 data.
oh[i] = data.
oYcrb[i] * ov;
70 data.
of[i] = ov.cross(data.
oh[i]);
71 data.
f[i] = data.
oMi[i].actInv(data.
of[i]);
74 ColsBlock J_cols = jmodel.jointCols(data.
J);
75 J_cols = data.
oMi[i].act(jdata.S());
83 typedef boost::fusion::vector<
const Model &,
90 template<
typename Jo
intModel>
95 Data::RowMatrixXd & Minv)
97 const Model::JointIndex & i = jmodel.id();
98 const Model::JointIndex & parent = model.
parents[i];
100 Inertia::Matrix6 & Ia = data.
Yaba[i];
101 jmodel.calc_aba(jdata.derived(), Ia, parent > 0);
108 ColsBlock U_cols = jmodel.jointCols(data.
IS);
109 forceSet::se3Action(data.
oMi[i],jdata.U(),U_cols);
111 Minv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),jmodel.nv()) = jdata.Dinv();
112 const int nv_children = data.
nvSubtree[i] - jmodel.nv();
115 ColsBlock J_cols = jmodel.jointCols(data.
J);
116 ColsBlock SDinv_cols = jmodel.jointCols(data.
SDinv);
117 SDinv_cols.noalias() = J_cols * jdata.Dinv();
119 Minv.block(jmodel.idx_v(),jmodel.idx_v()+jmodel.nv(),jmodel.nv(),nv_children).noalias()
120 = -SDinv_cols.transpose() * Fcrb.middleCols(jmodel.idx_v()+jmodel.nv(),nv_children);
124 FcrbTmp.leftCols(data.
nvSubtree[i]).noalias()
125 = U_cols * Minv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.
nvSubtree[i]);
126 Fcrb.middleCols(jmodel.idx_v(),data.
nvSubtree[i]) += FcrbTmp.leftCols(data.
nvSubtree[i]);
131 Fcrb.middleCols(jmodel.idx_v(),data.
nvSubtree[i]).noalias()
132 = U_cols * Minv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.
nvSubtree[i]);
135 jmodel.jointVelocitySelector(data.
u) -= jdata.S().transpose()*data.
f[i];
140 pa.
toVector() += Ia * data.
a[i].toVector() + jdata.UDinv() * jmodel.jointVelocitySelector(data.
u);
141 data.
Yaba[parent] += AbaBackwardStep::SE3actOn(data.
liMi[i], Ia);
142 data.
f[parent] += data.
liMi[i].act(pa);
151 typedef boost::fusion::vector<
const se3::Model &,
158 template<
typename Jo
intModel>
161 const se3::Model & model,
163 Data::RowMatrixXd & Minv)
165 const Model::JointIndex & i = jmodel.id();
166 const Model::Index & parent = model.
parents[i];
171 data.
a[i] += data.
liMi[i].actInv(data.
a[parent]);
172 jmodel.jointVelocitySelector(data.
ddq).noalias() =
173 jdata.Dinv() * jmodel.jointVelocitySelector(data.
u) - jdata.UDinv().transpose() * data.
a[i].toVector();
175 data.
a[i] += jdata.S() * jmodel.jointVelocitySelector(data.
ddq);
176 oa = data.
oMi[i].act(data.
a[i]);
177 of = data.
oYcrb[i] * oa + ov.cross(data.
oh[i]);
182 ColsBlock UDinv_cols = jmodel.jointCols(data.
UDinv);
183 forceSet::se3Action(data.
oMi[i],jdata.UDinv(),UDinv_cols);
187 FcrbTmp.topRows(jmodel.nv()).rightCols(model.
nv - jmodel.idx_v()).noalias()
188 = UDinv_cols.transpose() * data.
Fcrb[parent].rightCols(model.
nv - jmodel.idx_v());
189 Minv.middleRows(jmodel.idx_v(),jmodel.nv()).rightCols(model.
nv - jmodel.idx_v())
190 -= FcrbTmp.topRows(jmodel.nv()).rightCols(model.
nv - jmodel.idx_v());
193 ColsBlock J_cols = jmodel.jointCols(data.
J);
194 data.
Fcrb[i].rightCols(model.
nv - jmodel.idx_v()).noalias() = J_cols * Minv.middleRows(jmodel.idx_v(),jmodel.nv()).rightCols(model.
nv - jmodel.idx_v());
196 data.
Fcrb[i].rightCols(model.
nv - jmodel.idx_v()) += data.
Fcrb[parent].rightCols(model.
nv - jmodel.idx_v());
198 ColsBlock dJ_cols = jmodel.jointCols(data.
dJ);
199 ColsBlock dVdq_cols = jmodel.jointCols(data.
dVdq);
200 ColsBlock dAdq_cols = jmodel.jointCols(data.
dAdq);
201 ColsBlock dAdv_cols = jmodel.jointCols(data.
dAdv);
203 motionSet::motionAction(ov,J_cols,dJ_cols);
204 motionSet::motionAction(data.
oa[parent],J_cols,dAdq_cols);
208 motionSet::motionAction(data.
ov[parent],J_cols,dVdq_cols);
209 motionSet::motionAction<ADDTO>(data.
ov[parent],dVdq_cols,dAdq_cols);
210 dAdv_cols += dVdq_cols;
217 computeRNEADerivativesForwardStep::addForceCrossMatrix(data.
oh[i],data.
doYcrb[i]);
224 typedef boost::fusion::vector<
const Model &,
230 template<
typename Jo
intModel>
235 const Model::JointIndex & i = jmodel.id();
236 const Model::JointIndex & parent = model.
parents[i];
237 Data::RowMatrix6 & M6tmpR = data.
M6tmpR;
239 Eigen::MatrixXd & rnea_partial_dq = data.
dtau_dq;
240 Eigen::MatrixXd & rnea_partial_dv = data.
dtau_dv;
244 ColsBlock J_cols = jmodel.jointCols(data.
J);
245 ColsBlock dVdq_cols = jmodel.jointCols(data.
dVdq);
246 ColsBlock dAdq_cols = jmodel.jointCols(data.
dAdq);
247 ColsBlock dAdv_cols = jmodel.jointCols(data.
dAdv);
248 ColsBlock dFdq_cols = jmodel.jointCols(data.
dFdq);
249 ColsBlock dFdv_cols = jmodel.jointCols(data.
dFdv);
252 motionSet::inertiaAction(data.
oYcrb[i],dAdv_cols,dFdv_cols);
253 dFdv_cols += data.
doYcrb[i] * J_cols;
255 rnea_partial_dv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.
nvSubtree[i]).noalias()
256 = J_cols.transpose()*data.
dFdv.middleCols(jmodel.idx_v(),data.
nvSubtree[i]);
259 motionSet::inertiaAction(data.
oYcrb[i],dAdq_cols,dFdq_cols);
261 dFdq_cols += data.
doYcrb[i] * dVdq_cols;
263 rnea_partial_dq.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.
nvSubtree[i]).noalias()
264 = J_cols.transpose()*data.
dFdq.middleCols(jmodel.idx_v(),data.
nvSubtree[i]);
266 motionSet::act<ADDTO>(J_cols,data.
of[i],dFdq_cols);
270 lhsInertiaMult(data.
oYcrb[i],J_cols.transpose(),M6tmpR.topRows(jmodel.nv()));
272 rnea_partial_dq.middleRows(jmodel.idx_v(),jmodel.nv()).col(j).noalias() = M6tmpR.topRows(jmodel.nv()) * data.
dAdq.col(j);
274 rnea_partial_dv.middleRows(jmodel.idx_v(),jmodel.nv()).col(j).noalias() = M6tmpR.topRows(jmodel.nv()) * data.
dAdv.col(j);
276 M6tmpR.topRows(jmodel.nv()).noalias() = J_cols.transpose() * data.
doYcrb[i];
278 rnea_partial_dq.middleRows(jmodel.idx_v(),jmodel.nv()).col(j) += M6tmpR.topRows(jmodel.nv()) * data.
dVdq.col(j);
280 rnea_partial_dv.middleRows(jmodel.idx_v(),jmodel.nv()).col(j) += M6tmpR.topRows(jmodel.nv()) * data.
J.col(j);
287 data.
of[parent] += data.
of[i];
291 template<
typename Min,
typename Mout>
292 static void lhsInertiaMult(
const Inertia & Y,
293 const Eigen::MatrixBase<Min> & J,
294 const Eigen::MatrixBase<Mout> & F)
296 Mout & F_ =
const_cast<Mout &
>(F.derived());
297 motionSet::inertiaAction(Y,J.derived().transpose(),F_.transpose());
303 const Eigen::VectorXd & q,
304 const Eigen::VectorXd & v,
305 const Eigen::VectorXd & tau,
306 Eigen::MatrixXd & aba_partial_dq,
307 Eigen::MatrixXd & aba_partial_dv,
308 Data::RowMatrixXd & aba_partial_dtau)
310 assert(q.size() == model.
nq &&
"The joint configuration vector is not of right size");
311 assert(v.size() == model.
nv &&
"The joint velocity vector is not of right size");
312 assert(tau.size() == model.
nv &&
"The joint acceleration vector is not of right size");
313 assert(aba_partial_dq.cols() == model.
nv);
314 assert(aba_partial_dq.rows() == model.
nv);
315 assert(aba_partial_dv.cols() == model.
nv);
316 assert(aba_partial_dv.rows() == model.
nv);
317 assert(aba_partial_dtau.cols() == model.
nv);
318 assert(aba_partial_dtau.rows() == model.
nv);
319 assert(model.
check(data) &&
"data is not consistent with model.");
325 Data::RowMatrixXd & Minv = aba_partial_dtau;
328 for(Model::JointIndex i=1; i<(Model::JointIndex) model.
njoints; ++i)
330 computeABADerivativesForwardStep1::run(model.
joints[i],data.
joints[i],
331 computeABADerivativesForwardStep1::ArgsType(model,data,q,v));
334 data.
Fcrb[0].setZero();
335 for(
size_t i=(
size_t) (model.
njoints-1);i>0;--i)
337 computeABADerivativesBackwardStep1::run(model.
joints[i],data.
joints[i],
338 computeABADerivativesBackwardStep1::ArgsType(model,data,Minv));
341 for(Model::JointIndex i=1; i<(Model::JointIndex) model.
njoints; ++i)
343 computeABADerivativesForwardStep2::run(model.
joints[i],data.
joints[i],
344 computeABADerivativesForwardStep2::ArgsType(model,data,Minv));
347 for(
size_t i=(
size_t) (model.
njoints-1);i>0;--i)
349 computeABADerivativesBackwardStep2::run(model.
joints[i],
350 computeABADerivativesBackwardStep2::ArgsType(model,data));
353 Minv.triangularView<Eigen::StrictlyLower>()
354 = Minv.transpose().triangularView<Eigen::StrictlyLower>();
356 aba_partial_dq.noalias() = -Minv*data.
dtau_dq;
357 aba_partial_dv.noalias() = -Minv*data.
dtau_dv;
364 #endif // ifndef __se3_aba_derivatives_hxx__
container::aligned_vector< Force > oh
Vector of spatial momenta expressed in the world frame.
container::aligned_vector< Motion > a
Vector of joint accelerations expressed at the centers of the joints.
int nq
Dimension of the configuration vector representation.
void computeABADerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &tau, Eigen::MatrixXd &aba_partial_dq, Eigen::MatrixXd &aba_partial_dv, Data::RowMatrixXd &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
int nv
Dimension of the velocity vector space.
container::aligned_vector< SE3 > jointPlacements
Placement (SE3) of the input of joint i regarding to the parent joint output li.
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
container::aligned_vector< Inertia > oYcrb
Inertia quantities expressed in the world frame.
Eigen::VectorXd u
Intermediate quantity corresponding to apparent torque [ABA].
Eigen::MatrixXd dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity. ...
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
The 6d jacobian type (temporary)
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
Matrix6x J
Jacobian of joint placements.
container::aligned_vector< Motion > oa
Vector of joint accelerations expressed at the origin.
container::aligned_vector< Inertia::Matrix6 > doYcrb
Time variation of the inertia quantities expressed in the world frame.
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Eigen::VectorXd ddq
The joint accelerations computed from ABA.
container::aligned_vector< Force > of
Vector of body forces expressed in the world frame. For each body, the force represents the sum of al...
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
Matrix6x UDinv
Used in computeMinverse.
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Matrix6x SDinv
Used in computeMinverse.
container::aligned_vector< Inertia::Matrix6 > Yaba
Inertia matrix of the subtree expressed as dense matrix [ABA].
container::aligned_vector< Motion > ov
Vector of joint velocities expressed at the origin.
container::aligned_vector< Matrix6x > Fcrb
Spatial forces set, used in CRBA and CCRBA.
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
Matrix6x IS
Used in computeMinverse.
JointDataVector joints
Vector of se3::JointData associated to the se3::JointModel stored in model, encapsulated in JointData...
Motion gravity
Spatial gravity of the model.
container::aligned_vector< SE3 > liMi
Vector of relative joint placements (wrt the body parent).
container::aligned_vector< SE3 > oMi
Vector of absolute joint placements (wrt the world).
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
container::aligned_vector< Inertia > inertias
Spatial inertias of the body i expressed in the supporting joint frame i.
container::aligned_vector< Force > f
Vector of body forces expressed in the local frame of the joint. For each body, the force represents ...
RowMatrix6 M6tmpR
Temporary for derivative algorithms.
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Eigen::MatrixXd dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
container::aligned_vector< Motion > v
Vector of joint velocities expressed at the centers of the joints.
int njoints
Number of joints.