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/aba-derivatives.hpp" 19 template<
typename _Scalar>
49 CppAD::Independent(
ad_X);
51 Eigen::DenseIndex it = 0;
61 ad_fun.optimize(
"no_compare_op");
65 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
67 const Eigen::MatrixBase<TangentVector1> &
v,
68 const Eigen::MatrixBase<TangentVector2> & a)
71 Eigen::DenseIndex it = 0;
81 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
83 const Eigen::MatrixBase<TangentVector1> &
v,
84 const Eigen::MatrixBase<TangentVector2> & a)
87 Eigen::DenseIndex it = 0;
118 template<
typename _Scalar>
141 da_dq = MatrixXs::Zero(model.
nv,model.
nq);
142 da_dv = MatrixXs::Zero(model.
nv,model.
nv);
143 da_dtau = MatrixXs::Zero(model.
nv,model.
nv);
148 CppAD::Independent(
ad_X);
150 Eigen::DenseIndex it = 0;
159 ad_fun.optimize(
"no_compare_op");
163 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
165 const Eigen::MatrixBase<TangentVector1> &
v,
166 const Eigen::MatrixBase<TangentVector2> &
tau)
169 Eigen::DenseIndex it = 0;
179 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
181 const Eigen::MatrixBase<TangentVector1> &
v,
182 const Eigen::MatrixBase<TangentVector2> &
tau)
185 Eigen::DenseIndex it = 0;
217 template<
typename _Scalar>
238 M = MatrixXs::Zero(model.
nv,model.
nq);
245 CppAD::Independent(
ad_X);
247 Eigen::DenseIndex it = 0;
251 Eigen::DenseIndex it_Y = 0;
264 ad_fun.optimize(
"no_compare_op");
267 template<
typename ConfigVectorType>
271 Eigen::DenseIndex it = 0;
277 Eigen::DenseIndex it_Y = 0;
306 template<
typename _Scalar>
327 Minv = MatrixXs::Zero(model.
nv,model.
nq);
334 CppAD::Independent(
ad_X);
336 Eigen::DenseIndex it = 0;
340 Eigen::DenseIndex it_Y = 0;
352 ad_fun.optimize(
"no_compare_op");
355 template<
typename ConfigVectorType>
359 Eigen::DenseIndex it = 0;
365 Eigen::DenseIndex it_Y = 0;
392 template<
typename _Scalar>
421 ad_dtau_dq = ADMatrixXs::Zero(model.nv,model.nv);
422 ad_dtau_dv = ADMatrixXs::Zero(model.nv,model.nv);
423 ad_dtau_da = ADMatrixXs::Zero(model.nv,model.nv);
425 dtau_dq = MatrixXs::Zero(model.nv,model.nv);
426 dtau_dv = MatrixXs::Zero(model.nv,model.nv);
427 dtau_da = MatrixXs::Zero(model.nv,model.nv);
434 CppAD::Independent(
ad_X);
436 Eigen::DenseIndex it = 0;
443 ad_dtau_dq,ad_dtau_dv,ad_dtau_da);
447 Eigen::DenseIndex it_Y = 0;
456 ad_fun.optimize(
"no_compare_op");
459 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
461 const Eigen::MatrixBase<TangentVector1> &
v,
462 const Eigen::MatrixBase<TangentVector2> & a)
465 Eigen::DenseIndex it_x = 0;
473 Eigen::DenseIndex it_y = 0;
501 template<
typename _Scalar>
530 ad_dddq_dq = ADMatrixXs::Zero(model.nv,model.nv);
531 ad_dddq_dv = ADMatrixXs::Zero(model.nv,model.nv);
532 ad_dddq_dtau = ADMatrixXs::Zero(model.nv,model.nv);
534 dddq_dq = MatrixXs::Zero(model.nv,model.nv);
535 dddq_dv = MatrixXs::Zero(model.nv,model.nv);
536 dddq_dtau = MatrixXs::Zero(model.nv,model.nv);
543 CppAD::Independent(
ad_X);
545 Eigen::DenseIndex it = 0;
552 ad_dddq_dq,ad_dddq_dv,ad_dddq_dtau);
556 Eigen::DenseIndex it_Y = 0;
565 ad_fun.optimize(
"no_compare_op");
568 template<
typename ConfigVectorType,
typename TangentVector1,
typename TangentVector2>
570 const Eigen::MatrixBase<TangentVector1> &
v,
571 const Eigen::MatrixBase<TangentVector2> &
tau)
574 Eigen::DenseIndex it_x = 0;
582 Eigen::DenseIndex it_y = 0;
607 ADTangentVectorType
ad_v, ad_tau;
610 template<
typename _Scalar>
635 CppAD::Independent(
ad_X);
637 Eigen::DenseIndex it = 0;
643 ad_fun.optimize(
"no_compare_op");
647 template<
typename ConfigVectorType1,
typename TangentVector,
typename ConfigVectorType2>
649 const Eigen::MatrixBase<TangentVector> &
v,
650 const Eigen::MatrixBase<ConfigVectorType2> & qout)
653 Eigen::DenseIndex it = 0;
677 template<
typename _Scalar>
691 const std::string &
library_name =
"cg_difference_eval")
702 CppAD::Independent(
ad_X);
704 Eigen::DenseIndex it = 0;
710 ad_fun.optimize(
"no_compare_op");
714 template<
typename ConfigVectorType1,
typename ConfigVectorType2,
typename TangentVector>
716 const Eigen::MatrixBase<ConfigVectorType2> &
q1,
717 const Eigen::MatrixBase<TangentVector> &
v)
720 Eigen::DenseIndex it = 0;
744 template<
typename _Scalar>
760 const std::string &
library_name =
"cg_dDifference_eval")
772 CppAD::Independent(
ad_X);
774 Eigen::DenseIndex it = 0;
783 ad_fun.optimize(
"no_compare_op");
787 template<
typename ConfigVectorType1,
typename ConfigVectorType2,
typename JacobianMatrix>
789 const Eigen::MatrixBase<ConfigVectorType2> &
q1,
790 const Eigen::MatrixBase<JacobianMatrix> &
J,
794 Eigen::DenseIndex it = 0;
810 assert(
false &&
"Wrong argument");
832 #endif // ifndef __pinocchio_codegen_code_generator_algo_hpp__ void evalJacobian(const Eigen::MatrixBase< Vector > &x)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
void buildMap()
build the mapping Y = f(X)
void buildMap()
build the mapping Y = f(X)
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space...
Base::ADConfigVectorType ADConfigVectorType
TangentVectorType tau
Vector of joint torques (dim model.nv).
Base::ADConfigVectorType ADConfigVectorType
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
ADData::MatrixXs ADMatrixXs
VectorXs partial_derivatives
Base::ADTangentVectorType ADTangentVectorType
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
void evalFunction(const Eigen::MatrixBase< ConfigVectorType1 > &q0, const Eigen::MatrixBase< ConfigVectorType2 > &q1, const Eigen::MatrixBase< TangentVector > &v)
ADConfigVectorType ad_q_plus
CodeGenBase< _Scalar > Base
Base::ADTangentVectorType ADTangentVectorType
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.
ArgumentPosition
Argument position. Used as template parameter to refer to an argument.
void rnea(const int num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space...
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...
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q)
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...
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...
Base::ADConfigVectorType ADConfigVectorType
ADModel::ConfigVectorType ADConfigVectorType
CodeGenDDifference(const Model &model, const std::string &function_name="dDifference", const std::string &library_name="cg_dDifference_eval")
const std::string library_name
Name of the library.
Base::ADTangentVectorType ADTangentVectorType
void evalFunction(const Eigen::MatrixBase< ConfigVectorType1 > &q0, const Eigen::MatrixBase< ConfigVectorType2 > &q1, const Eigen::MatrixBase< JacobianMatrix > &J, const ArgumentPosition arg)
const std::string function_name
Name of the function.
CodeGenABA(const Model &model, const std::string &function_name="aba", const std::string &library_name="cg_aba_eval")
void buildMap()
build the mapping Y = f(X)
Eigen::Matrix< ADScalar, Eigen::Dynamic, 1, Options > ADVectorXs
Base::ADTangentVectorType ADTangentVectorType
void buildMap()
build the mapping Y = f(X)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
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...
CodeGenBase< _Scalar > Base
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
void buildMap()
build the mapping Y = f(X)
ADTangentVectorType ad_dq
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
CodeGenBase< _Scalar > Base
Base::ADConfigVectorType ADConfigVectorType
CodeGenBase< _Scalar > Base
CodeGenBase< _Scalar > Base
CodeGenIntegrate(const Model &model, const std::string &function_name="integrate", const std::string &library_name="cg_integrate_eval")
Base::ADTangentVectorType ADTangentVectorType
void evalJacobian(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & q1
void buildMap()
build the mapping Y = f(X)
TangentVectorType ddq
The joint accelerations computed from ABA.
void evalFunction(const Eigen::MatrixBase< Vector > &x)
void buildMap()
build the mapping Y = f(X)
CodeGenBase< _Scalar > Base
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
CodeGenBase< _Scalar > Base
CodeGenRNEA(const Model &model, const std::string &function_name="rnea", const std::string &library_name="cg_rnea_eval")
Base::ADConfigVectorType ADConfigVectorType
Main pinocchio namespace.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & q0
Base::ADConfigVectorType ADConfigVectorType
Base::ADConfigVectorType ADConfigVectorType
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
Base::ADTangentVectorType ADTangentVectorType
#define PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(D)
Similar to macro PINOCCHIO_EIGEN_PLAIN_TYPE but with guaranty to provite a row major type...
Eigen::DenseIndex getInputDimension() const
Dimension of the input vector.
ADData::MatrixXs ADMatrixXs
int nv
Dimension of the velocity vector space.
Base::ADConfigVectorType ADConfigVectorType
CodeGenMinv(const Model &model, const std::string &function_name="minv", const std::string &library_name="cg_minv_eval")
Base::ADVectorXs ADVectorXs
Base::ADTangentVectorType ADTangentVectorType
CodeGenCRBA(const Model &model, const std::string &function_name="crba", const std::string &library_name="cg_crba_eval")
ADModel::TangentVectorType ADTangentVectorType
Eigen::Matrix< ADScalar, Eigen::Dynamic, Eigen::Dynamic, Options > ADMatrixXs
void buildMap()
build the mapping Y = f(X)
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.
VectorXs partial_derivatives
Eigen::DenseIndex getOutputDimension() const
Dimension of the output vector.
CodeGenBase< _Scalar > Base
void evalFunction(const Eigen::MatrixBase< ConfigVectorType1 > &q, const Eigen::MatrixBase< TangentVector > &v, const Eigen::MatrixBase< ConfigVectorType2 > &qout)
Base::ADConfigVectorType ADConfigVectorType
CodeGenDifference(const Model &model, const std::string &function_name="difference", const std::string &library_name="cg_difference_eval")
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q)
CodeGenBase< _Scalar > Base
Base::ADTangentVectorType ADTangentVectorType
Base::ADTangentVectorType ADTangentVectorType
JointCollectionTpl & model
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options|Eigen::RowMajor > RowMatrixXs
int nq
Dimension of the configuration vector representation.
void evalJacobian(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
ADConfigVectorType ad_q_plus
void buildMap()
build the mapping Y = f(X)
Base::ADMatrixXs ADMatrixXs
bool build_jacobian
Options to build or not the Jacobian of he function.