5#ifndef __pinocchio_codegen_code_generator_algo_hpp__ 6#define __pinocchio_codegen_code_generator_algo_hpp__ 8#include "pinocchio/codegen/code-generator-base.hpp" 10#include "pinocchio/algorithm/joint-configuration.hpp" 11#include "pinocchio/algorithm/crba.hpp" 12#include "pinocchio/algorithm/rnea.hpp" 13#include "pinocchio/algorithm/aba.hpp" 14#include "pinocchio/algorithm/rnea-derivatives.hpp" 15#include "pinocchio/algorithm/constrained-dynamics-derivatives.hpp" 16#include "pinocchio/algorithm/constrained-dynamics.hpp" 17#include "pinocchio/algorithm/aba-derivatives.hpp" 21 template<
typename _Scalar>
22 struct CodeGenRNEA :
public CodeGenBase<_Scalar>
24 typedef CodeGenBase<_Scalar> Base;
25 typedef typename Base::Scalar Scalar;
27 typedef typename Base::Model Model;
28 typedef typename Base::ADConfigVectorType ADConfigVectorType;
29 typedef typename Base::ADTangentVectorType ADTangentVectorType;
30 typedef typename Base::MatrixXs MatrixXs;
31 typedef typename Base::VectorXs VectorXs;
39 ad_q = ADConfigVectorType(model.nq);
41 ad_v = ADTangentVectorType(model.nv);
43 ad_a = ADTangentVectorType(model.nv);
48 dtau_dq = MatrixXs::Zero(model.nv, model.nq);
49 dtau_dv = MatrixXs::Zero(model.nv, model.nv);
50 dtau_da = MatrixXs::Zero(model.nv, model.nv);
53 virtual ~CodeGenRNEA()
59 CppAD::Independent(ad_X);
61 Eigen::DenseIndex it = 0;
62 ad_q = ad_X.segment(it, ad_model.nq);
64 ad_v = ad_X.segment(it, ad_model.nv);
66 ad_a = ad_X.segment(it, ad_model.nv);
73 ad_fun.Dependent(ad_X, ad_Y);
74 ad_fun.optimize(
"no_compare_op");
77 using Base::evalFunction;
78 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
80 const Eigen::MatrixBase<ConfigVectorType> & q,
81 const Eigen::MatrixBase<TangentVector1> & v,
82 const Eigen::MatrixBase<TangentVector2> & a)
85 Eigen::DenseIndex it = 0;
86 x.segment(it, ad_model.
nq) = q;
88 x.segment(it, ad_model.
nv) = v;
90 x.segment(it, ad_model.
nv) = a;
97 using Base::evalJacobian;
98 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
100 const Eigen::MatrixBase<ConfigVectorType> & q,
101 const Eigen::MatrixBase<TangentVector1> & v,
102 const Eigen::MatrixBase<TangentVector2> & a)
105 Eigen::DenseIndex it = 0;
106 x.segment(it, ad_model.
nq) = q;
108 x.segment(it, ad_model.
nv) = v;
110 x.segment(it, ad_model.
nv) = a;
115 dtau_dq = Base::jac.middleCols(it, ad_model.
nq);
117 dtau_dv = Base::jac.middleCols(it, ad_model.
nv);
119 dtau_da = Base::jac.middleCols(it, ad_model.
nv);
123 MatrixXs dtau_dq, dtau_dv, dtau_da;
128 using Base::ad_model;
137 ADConfigVectorType ad_q, ad_q_plus;
138 ADTangentVectorType ad_dq, ad_v, ad_a;
141 template<
typename _Scalar>
142 struct CodeGenABA :
public CodeGenBase<_Scalar>
144 typedef CodeGenBase<_Scalar> Base;
145 typedef typename Base::Scalar Scalar;
147 typedef typename Base::Model Model;
148 typedef typename Base::ADConfigVectorType ADConfigVectorType;
149 typedef typename Base::ADTangentVectorType ADTangentVectorType;
150 typedef typename Base::MatrixXs MatrixXs;
151 typedef typename Base::VectorXs VectorXs;
159 ad_q = ADConfigVectorType(model.nq);
161 ad_v = ADTangentVectorType(model.nv);
163 ad_tau = ADTangentVectorType(model.nv);
168 da_dq = MatrixXs::Zero(model.nv, model.nq);
169 da_dv = MatrixXs::Zero(model.nv, model.nv);
170 da_dtau = MatrixXs::Zero(model.nv, model.nv);
173 virtual ~CodeGenABA()
179 CppAD::Independent(ad_X);
181 Eigen::DenseIndex it = 0;
182 ad_q = ad_X.segment(it, ad_model.nq);
184 ad_v = ad_X.segment(it, ad_model.nv);
186 ad_tau = ad_X.segment(it, ad_model.nv);
192 ad_fun.Dependent(ad_X, ad_Y);
193 ad_fun.optimize(
"no_compare_op");
196 using Base::evalFunction;
197 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
199 const Eigen::MatrixBase<ConfigVectorType> & q,
200 const Eigen::MatrixBase<TangentVector1> & v,
201 const Eigen::MatrixBase<TangentVector2> & tau)
204 Eigen::DenseIndex it = 0;
205 x.segment(it, ad_model.
nq) = q;
207 x.segment(it, ad_model.
nv) = v;
209 x.segment(it, ad_model.
nv) = tau;
216 using Base::evalJacobian;
217 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
219 const Eigen::MatrixBase<ConfigVectorType> & q,
220 const Eigen::MatrixBase<TangentVector1> & v,
221 const Eigen::MatrixBase<TangentVector2> & tau)
224 Eigen::DenseIndex it = 0;
225 x.segment(it, ad_model.
nq) = q;
227 x.segment(it, ad_model.
nv) = v;
229 x.segment(it, ad_model.
nv) = tau;
235 da_dq = Base::jac.middleCols(it, ad_model.
nq);
237 da_dv = Base::jac.middleCols(it, ad_model.
nv);
239 da_dtau = Base::jac.middleCols(it, ad_model.
nv);
243 MatrixXs da_dq, da_dv, da_dtau;
248 using Base::ad_model;
257 ADConfigVectorType ad_q, ad_q_plus;
258 ADTangentVectorType ad_dq, ad_v, ad_tau;
261 template<
typename _Scalar>
262 struct CodeGenCRBA :
public CodeGenBase<_Scalar>
264 typedef CodeGenBase<_Scalar> Base;
265 typedef typename Base::Scalar Scalar;
267 typedef typename Base::Model Model;
268 typedef typename Base::ADConfigVectorType ADConfigVectorType;
269 typedef typename Base::ADTangentVectorType ADTangentVectorType;
270 typedef typename Base::MatrixXs MatrixXs;
271 typedef typename Base::VectorXs VectorXs;
279 ad_q = ADConfigVectorType(model.nq);
284 M = MatrixXs::Zero(model.nv, model.nq);
289 virtual ~CodeGenCRBA()
295 CppAD::Independent(ad_X);
297 Eigen::DenseIndex it = 0;
298 ad_q = ad_X.segment(it, ad_model.nq);
302 Eigen::DenseIndex it_Y = 0;
304 for (Eigen::DenseIndex i = 0; i < ad_model.nv; ++i)
306 for (Eigen::DenseIndex j = i; j < ad_model.nv; ++j)
308 ad_Y[it_Y++] = ad_data.M(i, j);
314 ad_fun.Dependent(ad_X, ad_Y);
315 ad_fun.optimize(
"no_compare_op");
318 template<
typename ConfigVectorType>
319 void evalFunction(
const Eigen::MatrixBase<ConfigVectorType> & q)
322 Eigen::DenseIndex it = 0;
323 x.segment(it, ad_model.
nq) = q;
326 Base::evalFunction(x);
329 Eigen::DenseIndex it_Y = 0;
330 for (Eigen::DenseIndex i = 0; i < ad_model.
nv; ++i)
332 for (Eigen::DenseIndex j = i; j < ad_model.
nv; ++j)
334 M(i, j) = Base::y[it_Y++];
346 using Base::ad_model;
354 ADConfigVectorType ad_q;
357 template<
typename _Scalar>
358 struct CodeGenMinv :
public CodeGenBase<_Scalar>
360 typedef CodeGenBase<_Scalar> Base;
361 typedef typename Base::Scalar Scalar;
363 typedef typename Base::Model Model;
364 typedef typename Base::ADConfigVectorType ADConfigVectorType;
365 typedef typename Base::ADTangentVectorType ADTangentVectorType;
366 typedef typename Base::MatrixXs MatrixXs;
367 typedef typename Base::VectorXs VectorXs;
375 ad_q = ADConfigVectorType(model.nq);
380 Minv = MatrixXs::Zero(model.nv, model.nq);
385 virtual ~CodeGenMinv()
391 CppAD::Independent(ad_X);
393 Eigen::DenseIndex it = 0;
394 ad_q = ad_X.segment(it, ad_model.nq);
398 Eigen::DenseIndex it_Y = 0;
399 for (Eigen::DenseIndex i = 0; i < ad_model.nv; ++i)
401 for (Eigen::DenseIndex j = i; j < ad_model.nv; ++j)
403 ad_Y[it_Y++] = ad_data.Minv(i, j);
409 ad_fun.Dependent(ad_X, ad_Y);
410 ad_fun.optimize(
"no_compare_op");
413 template<
typename ConfigVectorType>
414 void evalFunction(
const Eigen::MatrixBase<ConfigVectorType> & q)
417 Eigen::DenseIndex it = 0;
418 x.segment(it, ad_model.
nq) = q;
421 Base::evalFunction(x);
424 Eigen::DenseIndex it_Y = 0;
425 for (Eigen::DenseIndex i = 0; i < ad_model.
nv; ++i)
427 for (Eigen::DenseIndex j = i; j < ad_model.
nv; ++j)
429 Minv(i, j) = Base::y[it_Y++];
439 using Base::ad_model;
447 ADConfigVectorType ad_q;
450 template<
typename _Scalar>
451 struct CodeGenRNEADerivatives :
public CodeGenBase<_Scalar>
453 typedef CodeGenBase<_Scalar> Base;
454 typedef typename Base::Scalar Scalar;
456 typedef typename Base::Model Model;
457 typedef typename Base::ADConfigVectorType ADConfigVectorType;
458 typedef typename Base::ADTangentVectorType ADTangentVectorType;
459 typedef typename Base::MatrixXs MatrixXs;
460 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(MatrixXs) RowMatrixXs;
461 typedef typename Base::VectorXs VectorXs;
463 typedef typename Base::ADData ADData;
464 typedef typename ADData::MatrixXs ADMatrixXs;
465 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(ADMatrixXs) RowADMatrixXs;
467 CodeGenRNEADerivatives(
470 const std::string &
library_name =
"cg_partial_rnea_eval")
473 ad_q = ADConfigVectorType(model.nq);
475 ad_v = ADTangentVectorType(model.nv);
477 ad_a = ADTangentVectorType(model.nv);
482 ad_dtau_dq = ADMatrixXs::Zero(model.nv, model.nv);
483 ad_dtau_dv = ADMatrixXs::Zero(model.nv, model.nv);
484 ad_dtau_da = ADMatrixXs::Zero(model.nv, model.nv);
486 dtau_dq = MatrixXs::Zero(model.nv, model.nv);
487 dtau_dv = MatrixXs::Zero(model.nv, model.nv);
488 dtau_da = MatrixXs::Zero(model.nv, model.nv);
493 virtual ~CodeGenRNEADerivatives()
499 CppAD::Independent(ad_X);
501 Eigen::DenseIndex it = 0;
502 ad_q = ad_X.segment(it, ad_model.nq);
504 ad_v = ad_X.segment(it, ad_model.nv);
506 ad_a = ad_X.segment(it, ad_model.nv);
510 ad_model, ad_data, ad_q, ad_v, ad_a, ad_dtau_dq, ad_dtau_dv, ad_dtau_da);
514 Eigen::DenseIndex it_Y = 0;
515 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_dtau_dq;
516 it_Y += ad_model.nv * ad_model.nv;
517 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_dtau_dv;
518 it_Y += ad_model.nv * ad_model.nv;
519 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_dtau_da;
520 it_Y += ad_model.nv * ad_model.nv;
522 ad_fun.Dependent(ad_X, ad_Y);
523 ad_fun.optimize(
"no_compare_op");
526 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
528 const Eigen::MatrixBase<ConfigVectorType> & q,
529 const Eigen::MatrixBase<TangentVector1> & v,
530 const Eigen::MatrixBase<TangentVector2> & a)
533 Eigen::DenseIndex it_x = 0;
534 x.segment(it_x, ad_model.
nq) = q;
536 x.segment(it_x, ad_model.
nv) = v;
538 x.segment(it_x, ad_model.
nv) = a;
541 Base::evalFunction(x);
544 Eigen::DenseIndex it_y = 0;
545 dtau_dq = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
546 it_y += ad_model.
nv * ad_model.
nv;
547 dtau_dv = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
548 it_y += ad_model.
nv * ad_model.
nv;
549 dtau_da = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
550 it_y += ad_model.
nv * ad_model.
nv;
556 using Base::ad_model;
562 ADMatrixXs ad_dtau_dq, ad_dtau_dv, ad_dtau_da;
563 MatrixXs dtau_dq, dtau_dv, dtau_da;
565 ADConfigVectorType ad_q;
566 ADTangentVectorType ad_v, ad_a;
569 template<
typename _Scalar>
570 struct CodeGenABADerivatives :
public CodeGenBase<_Scalar>
572 typedef CodeGenBase<_Scalar> Base;
573 typedef typename Base::Scalar Scalar;
575 typedef typename Base::Model Model;
576 typedef typename Base::ADConfigVectorType ADConfigVectorType;
577 typedef typename Base::ADTangentVectorType ADTangentVectorType;
578 typedef typename Base::MatrixXs MatrixXs;
579 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(MatrixXs) RowMatrixXs;
580 typedef typename Base::VectorXs VectorXs;
582 typedef typename Base::ADData ADData;
583 typedef typename ADData::MatrixXs ADMatrixXs;
584 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(ADMatrixXs) RowADMatrixXs;
586 CodeGenABADerivatives(
589 const std::string &
library_name =
"cg_partial_aba_eval")
592 ad_q = ADConfigVectorType(model.nq);
594 ad_v = ADTangentVectorType(model.nv);
596 ad_tau = ADTangentVectorType(model.nv);
601 ad_dddq_dq = ADMatrixXs::Zero(model.nv, model.nv);
602 ad_dddq_dv = ADMatrixXs::Zero(model.nv, model.nv);
603 ad_dddq_dtau = ADMatrixXs::Zero(model.nv, model.nv);
605 dddq_dq = MatrixXs::Zero(model.nv, model.nv);
606 dddq_dv = MatrixXs::Zero(model.nv, model.nv);
607 dddq_dtau = MatrixXs::Zero(model.nv, model.nv);
612 virtual ~CodeGenABADerivatives()
618 CppAD::Independent(ad_X);
620 Eigen::DenseIndex it = 0;
621 ad_q = ad_X.segment(it, ad_model.nq);
623 ad_v = ad_X.segment(it, ad_model.nv);
625 ad_tau = ad_X.segment(it, ad_model.nv);
629 ad_model, ad_data, ad_q, ad_v, ad_tau, ad_dddq_dq, ad_dddq_dv, ad_dddq_dtau);
633 Eigen::DenseIndex it_Y = 0;
634 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_dddq_dq;
635 it_Y += ad_model.nv * ad_model.nv;
636 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_dddq_dv;
637 it_Y += ad_model.nv * ad_model.nv;
638 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_dddq_dtau;
639 it_Y += ad_model.nv * ad_model.nv;
641 ad_fun.Dependent(ad_X, ad_Y);
642 ad_fun.optimize(
"no_compare_op");
645 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
647 const Eigen::MatrixBase<ConfigVectorType> & q,
648 const Eigen::MatrixBase<TangentVector1> & v,
649 const Eigen::MatrixBase<TangentVector2> & tau)
652 Eigen::DenseIndex it_x = 0;
653 x.segment(it_x, ad_model.
nq) = q;
655 x.segment(it_x, ad_model.
nv) = v;
657 x.segment(it_x, ad_model.
nv) = tau;
660 Base::evalFunction(x);
663 Eigen::DenseIndex it_y = 0;
664 dddq_dq = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
665 it_y += ad_model.
nv * ad_model.
nv;
666 dddq_dv = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
667 it_y += ad_model.
nv * ad_model.
nv;
668 dddq_dtau = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
669 it_y += ad_model.
nv * ad_model.
nv;
675 using Base::ad_model;
681 ADMatrixXs ad_dddq_dq, ad_dddq_dv, ad_dddq_dtau;
682 MatrixXs dddq_dq, dddq_dv, dddq_dtau;
684 ADConfigVectorType ad_q;
685 ADTangentVectorType ad_v, ad_tau;
688 template<
typename _Scalar>
689 struct CodeGenConstraintDynamicsDerivatives :
public CodeGenBase<_Scalar>
691 typedef CodeGenBase<_Scalar> Base;
692 typedef typename Base::Scalar Scalar;
693 typedef typename Base::ADScalar ADScalar;
695 typedef typename Base::Model Model;
697 typedef typename Base::ADConfigVectorType ADConfigVectorType;
698 typedef typename Base::ADTangentVectorType ADTangentVectorType;
699 typedef typename Base::MatrixXs MatrixXs;
700 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(MatrixXs) RowMatrixXs;
701 typedef typename Base::VectorXs VectorXs;
704 typedef Eigen::aligned_allocator<ContactModel> ConstraintModelAllocator;
705 typedef typename std::vector<ContactModel, ConstraintModelAllocator> ContactModelVector;
707 typedef Eigen::aligned_allocator<ContactData> ConstraintDataAllocator;
708 typedef typename std::vector<ContactData, ConstraintDataAllocator> ContactDataVector;
711 typedef Eigen::aligned_allocator<ADContactModel> ADConstraintModelAllocator;
712 typedef typename std::vector<ADContactModel, ADConstraintModelAllocator> ADContactModelVector;
714 typedef Eigen::aligned_allocator<ADContactData> ADConstraintDataAllocator;
715 typedef typename std::vector<ADContactData, ADConstraintDataAllocator> ADContactDataVector;
717 typedef typename Base::ADData ADData;
718 typedef typename ADData::MatrixXs ADMatrixXs;
719 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(ADMatrixXs) RowADMatrixXs;
721 Eigen::DenseIndex constraintDim(
const ContactModelVector & contact_models)
const 723 Eigen::DenseIndex num_total_constraints = 0;
724 for (
typename ContactModelVector::const_iterator it = contact_models.begin();
725 it != contact_models.end(); ++it)
727 PINOCCHIO_CHECK_INPUT_ARGUMENT(
728 it->size() > 0,
"The dimension of the constraint must be positive");
729 num_total_constraints += it->size();
731 return num_total_constraints;
734 CodeGenConstraintDynamicsDerivatives(
736 const ContactModelVector & contact_models,
737 const std::string &
function_name =
"partial_constraintDynamics",
738 const std::string &
library_name =
"cg_partial_constraintDynamics_eval")
741 model.nq + 2 * model.nv,
742 3 * model.nv * model.nv + 3 * constraintDim(contact_models) * model.nv,
745 , nc(constraintDim(contact_models))
746 , dddq_dq(model.nv, model.nv)
747 , dddq_dv(model.nv, model.nv)
748 , dddq_dtau(model.nv, model.nv)
750 dlambda_dq.resize(nc, model.nv);
751 dlambda_dq.setZero();
752 dlambda_dv.resize(nc, model.nv);
753 dlambda_dv.setZero();
754 dlambda_dtau.resize(nc, model.nv);
755 dlambda_dtau.setZero();
757 ad_q = ADConfigVectorType(model.nq);
759 ad_v = ADTangentVectorType(model.nv);
761 ad_tau = ADTangentVectorType(model.nv);
766 for (
int k = 0; k < contact_models.size(); ++k)
768 ad_contact_models.push_back(contact_models[k].
template cast<ADScalar>());
771 for (
int k = 0; k < ad_contact_models.size(); ++k)
773 ad_contact_datas.push_back(ADContactData(ad_contact_models[k]));
780 virtual ~CodeGenConstraintDynamicsDerivatives()
786 CppAD::Independent(ad_X);
788 Eigen::DenseIndex it = 0;
789 ad_q = ad_X.segment(it, ad_model.nq);
791 ad_v = ad_X.segment(it, ad_model.nv);
793 ad_tau = ad_X.segment(it, ad_model.nv);
797 ad_model, ad_data, ad_q, ad_v, ad_tau, ad_contact_models, ad_contact_datas);
798 pinocchio::computeConstraintDynamicsDerivatives(
799 ad_model, ad_data, ad_contact_models, ad_contact_datas);
802 Eigen::DenseIndex it_Y = 0;
803 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_data.ddq_dq;
804 it_Y += ad_model.nv * ad_model.nv;
805 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_data.ddq_dv;
806 it_Y += ad_model.nv * ad_model.nv;
807 Eigen::Map<RowADMatrixXs>(ad_Y.data() + it_Y, ad_model.nv, ad_model.nv) = ad_data.ddq_dtau;
808 it_Y += ad_model.nv * ad_model.nv;
809 Eigen::Map<ADMatrixXs>(ad_Y.data() + it_Y, nc, ad_model.nv) = ad_data.dlambda_dq;
810 it_Y += nc * ad_model.nv;
811 Eigen::Map<ADMatrixXs>(ad_Y.data() + it_Y, nc, ad_model.nv) = ad_data.dlambda_dv;
812 it_Y += nc * ad_model.nv;
813 Eigen::Map<ADMatrixXs>(ad_Y.data() + it_Y, nc, ad_model.nv) = ad_data.dlambda_dtau;
814 it_Y += nc * ad_model.nv;
815 ad_fun.Dependent(ad_X, ad_Y);
816 ad_fun.optimize(
"no_compare_op");
819 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
821 const Eigen::MatrixBase<ConfigVectorType> & q,
822 const Eigen::MatrixBase<TangentVector1> & v,
823 const Eigen::MatrixBase<TangentVector2> & tau)
826 Eigen::DenseIndex it_x = 0;
827 x.segment(it_x, ad_model.
nq) = q;
829 x.segment(it_x, ad_model.
nv) = v;
831 x.segment(it_x, ad_model.
nv) = tau;
834 Base::evalFunction(x);
837 Eigen::DenseIndex it_y = 0;
838 dddq_dq = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
839 it_y += ad_model.
nv * ad_model.
nv;
840 dddq_dv = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
841 it_y += ad_model.
nv * ad_model.
nv;
842 dddq_dtau = Eigen::Map<RowMatrixXs>(Base::y.data() + it_y, ad_model.
nv, ad_model.
nv);
843 it_y += ad_model.
nv * ad_model.
nv;
844 dlambda_dq = Eigen::Map<MatrixXs>(Base::y.data() + it_y, nc, ad_model.
nv);
845 it_y += nc * ad_model.
nv;
846 dlambda_dv = Eigen::Map<MatrixXs>(Base::y.data() + it_y, nc, ad_model.
nv);
847 it_y += nc * ad_model.
nv;
848 dlambda_dtau = Eigen::Map<MatrixXs>(Base::y.data() + it_y, nc, ad_model.
nv);
849 it_y += nc * ad_model.
nv;
855 using Base::ad_model;
860 Eigen::DenseIndex nc;
861 ADContactModelVector ad_contact_models;
862 ADContactDataVector ad_contact_datas;
865 MatrixXs dddq_dq, dddq_dv, dddq_dtau;
866 MatrixXs dlambda_dq, dlambda_dv, dlambda_dtau;
868 ADConfigVectorType ad_q;
869 ADTangentVectorType ad_v, ad_tau;
872 template<
typename _Scalar>
873 struct CodeGenConstraintDynamics :
public CodeGenBase<_Scalar>
875 typedef CodeGenBase<_Scalar> Base;
876 typedef typename Base::Scalar Scalar;
877 typedef typename Base::ADScalar ADScalar;
879 typedef typename Base::Model Model;
881 typedef typename Base::ADConfigVectorType ADConfigVectorType;
882 typedef typename Base::ADTangentVectorType ADTangentVectorType;
883 typedef typename Base::MatrixXs MatrixXs;
884 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(MatrixXs) RowMatrixXs;
885 typedef typename Base::VectorXs VectorXs;
888 typedef Eigen::aligned_allocator<ContactModel> ConstraintModelAllocator;
889 typedef typename std::vector<ContactModel, ConstraintModelAllocator> ContactModelVector;
891 typedef Eigen::aligned_allocator<ContactData> ConstraintDataAllocator;
892 typedef typename std::vector<ContactData, ConstraintDataAllocator> ContactDataVector;
895 typedef Eigen::aligned_allocator<ADContactModel> ADConstraintModelAllocator;
896 typedef typename std::vector<ADContactModel, ADConstraintModelAllocator> ADContactModelVector;
898 typedef Eigen::aligned_allocator<ADContactData> ADConstraintDataAllocator;
899 typedef typename std::vector<ADContactData, ADConstraintDataAllocator> ADContactDataVector;
901 typedef typename Base::ADData ADData;
902 typedef typename ADData::MatrixXs ADMatrixXs;
903 typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(ADMatrixXs) RowADMatrixXs;
905 Eigen::DenseIndex constraintDim(
const ContactModelVector & contact_models)
const 907 Eigen::DenseIndex num_total_constraints = 0;
908 for (
typename ContactModelVector::const_iterator it = contact_models.begin();
909 it != contact_models.end(); ++it)
911 PINOCCHIO_CHECK_INPUT_ARGUMENT(
912 it->size() > 0,
"The dimension of the constraint must be positive");
913 num_total_constraints += it->size();
915 return num_total_constraints;
918 CodeGenConstraintDynamics(
920 const ContactModelVector & contact_models,
922 const std::string &
library_name =
"cg_constraintDynamics_eval")
925 model.nq + 2 * model.nv,
926 model.nv + constraintDim(contact_models),
929 , nc(constraintDim(contact_models))
930 , da_dq(MatrixXs::Zero(model.nv, model.nq))
931 , da_dv(MatrixXs::Zero(model.nv, model.nv))
932 , da_dtau(MatrixXs::Zero(model.nv, model.nv))
937 dlambda_dq.resize(nc, model.nq);
938 dlambda_dq.setZero();
939 dlambda_dv.resize(nc, model.nv);
940 dlambda_dv.setZero();
941 dlambda_dtau.resize(nc, model.nv);
942 dlambda_dtau.setZero();
944 ad_q = ADConfigVectorType(model.nq);
946 ad_v = ADTangentVectorType(model.nv);
948 ad_tau = ADTangentVectorType(model.nv);
953 for (
int k = 0; k < contact_models.size(); ++k)
955 ad_contact_models.push_back(contact_models[k].
template cast<ADScalar>());
958 for (
int k = 0; k < ad_contact_models.size(); ++k)
960 ad_contact_datas.push_back(ADContactData(ad_contact_models[k]));
965 virtual ~CodeGenConstraintDynamics()
971 CppAD::Independent(ad_X);
973 Eigen::DenseIndex it = 0;
974 ad_q = ad_X.segment(it, ad_model.nq);
976 ad_v = ad_X.segment(it, ad_model.nv);
978 ad_tau = ad_X.segment(it, ad_model.nv);
982 ad_model, ad_data, ad_q, ad_v, ad_tau, ad_contact_models, ad_contact_datas);
983 ad_Y.head(ad_model.nv) = ad_data.ddq;
984 ad_Y.segment(ad_model.nv, nc) = ad_data.lambda_c;
986 ad_fun.Dependent(ad_X, ad_Y);
987 ad_fun.optimize(
"no_compare_op");
990 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
992 const Eigen::MatrixBase<ConfigVectorType> & q,
993 const Eigen::MatrixBase<TangentVector1> & v,
994 const Eigen::MatrixBase<TangentVector2> & tau)
997 Eigen::DenseIndex it_x = 0;
998 x.segment(it_x, ad_model.
nq) = q;
1000 x.segment(it_x, ad_model.
nv) = v;
1001 it_x += ad_model.
nv;
1002 x.segment(it_x, ad_model.
nv) = tau;
1003 it_x += ad_model.
nv;
1005 Base::evalFunction(x);
1007 Eigen::DenseIndex it_y = 0;
1008 ddq = Base::y.segment(it_y, ad_model.
nv);
1009 it_y += ad_model.
nv;
1010 lambda_c = Base::y.segment(it_y, nc);
1013 using Base::evalJacobian;
1014 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
1016 const Eigen::MatrixBase<ConfigVectorType> & q,
1017 const Eigen::MatrixBase<TangentVector1> & v,
1018 const Eigen::MatrixBase<TangentVector2> & a)
1021 Eigen::DenseIndex it = 0;
1022 x.segment(it, ad_model.
nq) = q;
1024 x.segment(it, ad_model.
nv) = v;
1026 x.segment(it, ad_model.
nv) = a;
1031 da_dq = Base::jac.middleCols(it, ad_model.
nq).topRows(ad_model.
nv);
1032 dlambda_dq = Base::jac.middleCols(it, ad_model.
nq).bottomRows(nc);
1034 da_dv = Base::jac.middleCols(it, ad_model.
nv).topRows(ad_model.
nv);
1035 dlambda_dv = Base::jac.middleCols(it, ad_model.
nv).bottomRows(nc);
1037 da_dtau = Base::jac.middleCols(it, ad_model.
nv).topRows(ad_model.
nv);
1038 dlambda_dtau = Base::jac.middleCols(it, ad_model.
nv).bottomRows(nc);
1041 VectorXs lambda_c, ddq;
1042 MatrixXs da_dq, da_dv, da_dtau;
1043 MatrixXs dlambda_dq, dlambda_dv, dlambda_dtau;
1046 using Base::ad_data;
1048 using Base::ad_model;
1053 ADContactModelVector ad_contact_models;
1054 ADContactDataVector ad_contact_datas;
1056 Eigen::DenseIndex nc;
1059 ADConfigVectorType ad_q;
1060 ADTangentVectorType ad_v, ad_tau;
1063 template<
typename _Scalar>
1064 struct CodeGenIntegrate :
public CodeGenBase<_Scalar>
1066 typedef CodeGenBase<_Scalar> Base;
1067 typedef typename Base::Scalar Scalar;
1069 typedef typename Base::Model Model;
1070 typedef typename Base::ADConfigVectorType ADConfigVectorType;
1071 typedef typename Base::ADTangentVectorType ADTangentVectorType;
1072 typedef typename Base::MatrixXs MatrixXs;
1073 typedef typename Base::VectorXs VectorXs;
1076 const Model & model,
1078 const std::string &
library_name =
"cg_integrate_eval")
1081 ad_q = ADConfigVectorType(model.nq);
1083 ad_v = ADTangentVectorType(model.nv);
1091 CppAD::Independent(ad_X);
1093 Eigen::DenseIndex it = 0;
1094 ad_q = ad_X.segment(it, ad_model.nq);
1096 ad_v = ad_X.segment(it, ad_model.nv);
1099 ad_fun.Dependent(ad_X, ad_Y);
1100 ad_fun.optimize(
"no_compare_op");
1103 using Base::evalFunction;
1104 template<
typename ConfigVectorType1,
typename TangentVector,
typename ConfigVectorType2>
1106 const Eigen::MatrixBase<ConfigVectorType1> & q,
1107 const Eigen::MatrixBase<TangentVector> & v,
1108 const Eigen::MatrixBase<ConfigVectorType2> & qout)
1111 Eigen::DenseIndex it = 0;
1112 x.segment(it, ad_model.
nq) = q;
1114 x.segment(it, ad_model.
nv) = v;
1117 PINOCCHIO_EIGEN_CONST_CAST(ConfigVectorType2, qout) = Base::y;
1122 using Base::ad_model;
1130 ADConfigVectorType ad_q;
1131 ADTangentVectorType ad_v;
1134 template<
typename _Scalar>
1135 struct CodeGenDifference :
public CodeGenBase<_Scalar>
1137 typedef CodeGenBase<_Scalar> Base;
1138 typedef typename Base::Scalar Scalar;
1140 typedef typename Base::Model Model;
1141 typedef typename Base::ADConfigVectorType ADConfigVectorType;
1142 typedef typename Base::ADTangentVectorType ADTangentVectorType;
1143 typedef typename Base::MatrixXs MatrixXs;
1144 typedef typename Base::VectorXs VectorXs;
1147 const Model & model,
1149 const std::string &
library_name =
"cg_difference_eval")
1152 ad_q0 = ADConfigVectorType(model.nq);
1154 ad_q1 = ADConfigVectorType(model.nq);
1162 CppAD::Independent(ad_X);
1164 Eigen::DenseIndex it = 0;
1165 ad_q0 = ad_X.segment(it, ad_model.nq);
1167 ad_q1 = ad_X.segment(it, ad_model.nq);
1170 ad_fun.Dependent(ad_X, ad_Y);
1171 ad_fun.optimize(
"no_compare_op");
1174 using Base::evalFunction;
1175 template<
typename ConfigVectorType1,
typename ConfigVectorType2,
typename TangentVector>
1177 const Eigen::MatrixBase<ConfigVectorType1> & q0,
1178 const Eigen::MatrixBase<ConfigVectorType2> & q1,
1179 const Eigen::MatrixBase<TangentVector> & v)
1182 Eigen::DenseIndex it = 0;
1183 x.segment(it, ad_model.
nq) = q0;
1185 x.segment(it, ad_model.
nq) = q1;
1188 PINOCCHIO_EIGEN_CONST_CAST(TangentVector, v) = Base::y;
1193 using Base::ad_model;
1201 ADConfigVectorType ad_q0;
1202 ADConfigVectorType ad_q1;
1205 template<
typename _Scalar>
1206 struct CodeGenDDifference :
public CodeGenBase<_Scalar>
1208 typedef CodeGenBase<_Scalar> Base;
1209 typedef typename Base::Scalar Scalar;
1211 typedef typename Base::Model Model;
1212 typedef typename Base::ADConfigVectorType ADConfigVectorType;
1213 typedef typename Base::ADTangentVectorType ADTangentVectorType;
1214 typedef typename Base::ADVectorXs ADVectorXs;
1215 typedef typename Base::ADMatrixXs ADMatrixXs;
1216 typedef typename Base::MatrixXs MatrixXs;
1217 typedef typename Base::VectorXs VectorXs;
1220 const Model & model,
1222 const std::string &
library_name =
"cg_dDifference_eval")
1227 ad_J0 = ADMatrixXs::Zero(ad_model.nv, ad_model.nv);
1228 ad_J1 = ADMatrixXs::Zero(ad_model.nv, ad_model.nv);
1234 CppAD::Independent(ad_X);
1236 Eigen::DenseIndex it = 0;
1237 ad_q0 = ad_X.segment(it, ad_model.nq);
1239 ad_q1 = ad_X.segment(it, ad_model.nq);
1243 Eigen::Map<ADMatrixXs>(ad_Y.data(), 2 * ad_model.nv, ad_model.nv).topRows(ad_model.nv) =
1245 Eigen::Map<ADMatrixXs>(ad_Y.data(), 2 * ad_model.nv, ad_model.nv).bottomRows(ad_model.nv) =
1247 ad_fun.Dependent(ad_X, ad_Y);
1248 ad_fun.optimize(
"no_compare_op");
1251 using Base::evalFunction;
1252 template<
typename ConfigVectorType1,
typename ConfigVectorType2,
typename JacobianMatrix>
1254 const Eigen::MatrixBase<ConfigVectorType1> & q0,
1255 const Eigen::MatrixBase<ConfigVectorType2> & q1,
1256 const Eigen::MatrixBase<JacobianMatrix> & J,
1260 Eigen::DenseIndex it = 0;
1261 x.segment(it, ad_model.
nq) = q0;
1263 x.segment(it, ad_model.
nq) = q1;
1268 case pinocchio::ARG0:
1269 PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrix, J) =
1270 Eigen::Map<MatrixXs>(Base::y.data(), 2 * ad_model.
nv, ad_model.
nv).topRows(ad_model.
nv);
1272 case pinocchio::ARG1:
1273 PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrix, J) =
1274 Eigen::Map<MatrixXs>(Base::y.data(), 2 * ad_model.
nv, ad_model.
nv)
1275 .bottomRows(ad_model.
nv);
1278 assert(
false &&
"Wrong argument");
1284 using Base::ad_model;
1290 ADConfigVectorType ad_q0;
1291 ADConfigVectorType ad_q1;
Main pinocchio namespace.
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
ArgumentPosition
Argument position. Used as template parameter to refer to an argument.
void difference(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &q0, const Eigen::MatrixBase< ConfigVectorIn2 > &q1, const Eigen::MatrixBase< ReturnType > &dvout)
Compute the tangent vector that must be integrated during one unit time to go from q0 to q1.
void initConstraintDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models)
Init the forward dynamics data according to the contact information contained in contact_models.
void computeABADerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Eigen::MatrixBase< MatrixType1 > &aba_partial_dq, const Eigen::MatrixBase< MatrixType2 > &aba_partial_dv, const Eigen::MatrixBase< MatrixType3 > &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & constraintDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings)
Computes the forward dynamics with contact constraints according to a given list of contact informati...
void computeRNEADerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da)
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint c...
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
void integrate(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout)
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & aba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const Convention convention=Convention::LOCAL)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & computeMinverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
void dDifference(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVector1 > &q0, const Eigen::MatrixBase< ConfigVector2 > &q1, const Eigen::MatrixBase< JacobianMatrix > &J, const ArgumentPosition arg)
Computes the Jacobian of a small variation of the configuration vector into the tangent space at iden...
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
Eigen::DenseIndex getOutputDimension() const
Dimension of the output vector.
Eigen::DenseIndex getInputDimension() const
Dimension of the input vector.
bool build_jacobian
Options to build or not the Jacobian of he function.
const std::string function_name
Name of the function.
const std::string library_name
Name of the library.
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
int nq
Dimension of the configuration vector representation.
int nv
Dimension of the velocity vector space.