Public Types | Public Member Functions | Protected Attributes | List of all members
pinocchio::CodeGenABADerivatives< _Scalar > Struct Template Reference

#include <code-generator-algo.hpp>

Inheritance diagram for pinocchio::CodeGenABADerivatives< _Scalar >:
Inheritance graph
[legend]

Public Types

typedef Base::ADConfigVectorType ADConfigVectorType
 
typedef Base::ADData ADData
 
typedef ADData::MatrixXs ADMatrixXs
 
typedef Base::ADTangentVectorType ADTangentVectorType
 
typedef CodeGenBase< _Scalar > Base
 
typedef Base::MatrixXs MatrixXs
 
typedef Base::Model Model
 
typedef Base::Scalar Scalar
 
typedef Base::VectorXs VectorXs
 
- Public Types inherited from pinocchio::CodeGenBase< _Scalar >
enum  { Options = 0 }
 
typedef ADModel::ConfigVectorType ADConfigVectorType
 
typedef pinocchio::DataTpl< ADScalar, OptionsADData
 
typedef CppAD::ADFun< CGScalarADFun
 
typedef Eigen::Matrix< ADScalar, Eigen::Dynamic, Eigen::Dynamic, OptionsADMatrixXs
 
typedef pinocchio::ModelTpl< ADScalar, OptionsADModel
 
typedef CppAD::AD< CGScalarADScalar
 
typedef ADModel::TangentVectorType ADTangentVectorType
 
typedef Eigen::Matrix< ADScalar, Eigen::Dynamic, 1, OptionsADVectorXs
 
typedef pinocchio::DataTpl< CGScalar, OptionsCGData
 
typedef pinocchio::ModelTpl< CGScalar, OptionsCGModel
 
typedef CppAD::cg::CG< ScalarCGScalar
 
typedef Model::ConfigVectorType ConfigVectorType
 
typedef pinocchio::DataTpl< Scalar, OptionsData
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, OptionsMatrixXs
 
typedef pinocchio::ModelTpl< Scalar, OptionsModel
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options|Eigen::RowMajor > RowMatrixXs
 
typedef _Scalar Scalar
 
typedef Model::TangentVectorType TangentVectorType
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, OptionsVectorXs
 

Public Member Functions

void buildMap ()
 build the mapping Y = f(X) More...
 
 CodeGenABADerivatives (const Model &model, const std::string &function_name="partial_aba", const std::string &library_name="cg_partial_aba_eval")
 
template<typename ConfigVectorType , typename TangentVector1 , typename TangentVector2 >
void evalFunction (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
 
typedef PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE (ADMatrixXs) RowADMatrixXs
 
typedef PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE (MatrixXs) RowMatrixXs
 
- Public Member Functions inherited from pinocchio::CodeGenBase< _Scalar >
 CodeGenBase (const Model &model, const Eigen::DenseIndex dim_input, const Eigen::DenseIndex dim_output, const std::string &function_name, const std::string &library_name)
 
CppAD::cg::ModelCSourceGen< Scalar > & codeGenerator ()
 
void compileAndLoadLib (const std::string &gccPath)
 
void compileLib (const std::string &gccPath="/usr/bin/gcc")
 
template<typename Vector >
void evalFunction (const Eigen::MatrixBase< Vector > &x)
 
template<typename Vector >
void evalJacobian (const Eigen::MatrixBase< Vector > &x)
 
bool existLib () const
 
Eigen::DenseIndex getInputDimension () const
 Dimension of the input vector. More...
 
Eigen::DenseIndex getOutputDimension () const
 Dimension of the output vector. More...
 
void initLib ()
 
void loadLib (const bool generate_if_not_exist=true)
 

Protected Attributes

ADData ad_data
 
ADMatrixXs ad_dddq_dq
 
ADMatrixXs ad_dddq_dtau
 
ADMatrixXs ad_dddq_dv
 
ADFun ad_fun
 
ADModel ad_model
 
ADConfigVectorType ad_q
 
ADTangentVectorType ad_tau
 
ADTangentVectorType ad_v
 
ADVectorXs ad_X
 
ADVectorXs ad_Y
 
MatrixXs dddq_dq
 
MatrixXs dddq_dtau
 
MatrixXs dddq_dv
 
VectorXs partial_derivatives
 
VectorXs x
 
VectorXs y
 
- Protected Attributes inherited from pinocchio::CodeGenBase< _Scalar >
ADTangentVectorType ad_a
 
ADData ad_data
 
ADTangentVectorType ad_dq
 
ADFun ad_fun
 
ADModel ad_model
 
ADConfigVectorType ad_q
 
ADConfigVectorType ad_q_plus
 
ADTangentVectorType ad_v
 
ADVectorXs ad_X
 
ADVectorXs ad_Y
 
bool build_forward
 Options to generate or not the source code for the evaluation function. More...
 
bool build_jacobian
 Options to build or not the Jacobian of he function. More...
 
std::unique_ptr< CppAD::cg::ModelCSourceGen< Scalar > > cgen_ptr
 
std::unique_ptr< CppAD::cg::DynamicLib< Scalar > > dynamicLib_ptr
 
std::unique_ptr< CppAD::cg::DynamicModelLibraryProcessor< Scalar > > dynamicLibManager_ptr
 
const std::string function_name
 Name of the function. More...
 
std::unique_ptr< CppAD::cg::GenericModel< Scalar > > generatedFun_ptr
 
RowMatrixXs jac
 
std::unique_ptr< CppAD::cg::ModelLibraryCSourceGen< Scalar > > libcgen_ptr
 
const std::string library_name
 Name of the library. More...
 
VectorXs y
 

Detailed Description

template<typename _Scalar>
struct pinocchio::CodeGenABADerivatives< _Scalar >

Definition at line 502 of file code-generator-algo.hpp.

Member Typedef Documentation

◆ ADConfigVectorType

template<typename _Scalar >
typedef Base::ADConfigVectorType pinocchio::CodeGenABADerivatives< _Scalar >::ADConfigVectorType

Definition at line 508 of file code-generator-algo.hpp.

◆ ADData

template<typename _Scalar >
typedef Base::ADData pinocchio::CodeGenABADerivatives< _Scalar >::ADData

Definition at line 514 of file code-generator-algo.hpp.

◆ ADMatrixXs

template<typename _Scalar >
typedef ADData::MatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::ADMatrixXs

Definition at line 515 of file code-generator-algo.hpp.

◆ ADTangentVectorType

template<typename _Scalar >
typedef Base::ADTangentVectorType pinocchio::CodeGenABADerivatives< _Scalar >::ADTangentVectorType

Definition at line 509 of file code-generator-algo.hpp.

◆ Base

template<typename _Scalar >
typedef CodeGenBase<_Scalar> pinocchio::CodeGenABADerivatives< _Scalar >::Base

Definition at line 504 of file code-generator-algo.hpp.

◆ MatrixXs

template<typename _Scalar >
typedef Base::MatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::MatrixXs

Definition at line 510 of file code-generator-algo.hpp.

◆ Model

template<typename _Scalar >
typedef Base::Model pinocchio::CodeGenABADerivatives< _Scalar >::Model

Definition at line 507 of file code-generator-algo.hpp.

◆ Scalar

template<typename _Scalar >
typedef Base::Scalar pinocchio::CodeGenABADerivatives< _Scalar >::Scalar

Definition at line 505 of file code-generator-algo.hpp.

◆ VectorXs

template<typename _Scalar >
typedef Base::VectorXs pinocchio::CodeGenABADerivatives< _Scalar >::VectorXs

Definition at line 512 of file code-generator-algo.hpp.

Constructor & Destructor Documentation

◆ CodeGenABADerivatives()

template<typename _Scalar >
pinocchio::CodeGenABADerivatives< _Scalar >::CodeGenABADerivatives ( const Model model,
const std::string &  function_name = "partial_aba",
const std::string &  library_name = "cg_partial_aba_eval" 
)
inline

Definition at line 518 of file code-generator-algo.hpp.

Member Function Documentation

◆ buildMap()

template<typename _Scalar >
void pinocchio::CodeGenABADerivatives< _Scalar >::buildMap ( )
inlinevirtual

build the mapping Y = f(X)

Implements pinocchio::CodeGenBase< _Scalar >.

Definition at line 541 of file code-generator-algo.hpp.

◆ evalFunction()

template<typename _Scalar >
template<typename ConfigVectorType , typename TangentVector1 , typename TangentVector2 >
void pinocchio::CodeGenABADerivatives< _Scalar >::evalFunction ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVector1 > &  v,
const Eigen::MatrixBase< TangentVector2 > &  tau 
)
inline

Definition at line 569 of file code-generator-algo.hpp.

◆ PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE() [1/2]

template<typename _Scalar >
typedef pinocchio::CodeGenABADerivatives< _Scalar >::PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE ( ADMatrixXs  )

◆ PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE() [2/2]

template<typename _Scalar >
typedef pinocchio::CodeGenABADerivatives< _Scalar >::PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE ( MatrixXs  )

Member Data Documentation

◆ ad_data

template<typename _Scalar >
ADData pinocchio::CodeGenBase< _Scalar >::ad_data
protected

Definition at line 153 of file code-generator-base.hpp.

◆ ad_dddq_dq

template<typename _Scalar >
ADMatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::ad_dddq_dq
protected

Definition at line 603 of file code-generator-algo.hpp.

◆ ad_dddq_dtau

template<typename _Scalar >
ADMatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::ad_dddq_dtau
protected

Definition at line 603 of file code-generator-algo.hpp.

◆ ad_dddq_dv

template<typename _Scalar >
ADMatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::ad_dddq_dv
protected

Definition at line 603 of file code-generator-algo.hpp.

◆ ad_fun

template<typename _Scalar >
ADFun pinocchio::CodeGenBase< _Scalar >::ad_fun
protected

Definition at line 167 of file code-generator-base.hpp.

◆ ad_model

template<typename _Scalar >
ADModel pinocchio::CodeGenBase< _Scalar >::ad_model
protected

Definition at line 152 of file code-generator-base.hpp.

◆ ad_q

template<typename _Scalar >
ADConfigVectorType pinocchio::CodeGenABADerivatives< _Scalar >::ad_q
protected

Definition at line 606 of file code-generator-algo.hpp.

◆ ad_tau

template<typename _Scalar >
ADTangentVectorType pinocchio::CodeGenABADerivatives< _Scalar >::ad_tau
protected

Definition at line 607 of file code-generator-algo.hpp.

◆ ad_v

template<typename _Scalar >
ADTangentVectorType pinocchio::CodeGenABADerivatives< _Scalar >::ad_v
protected

Definition at line 607 of file code-generator-algo.hpp.

◆ ad_X

template<typename _Scalar >
ADVectorXs pinocchio::CodeGenBase< _Scalar >::ad_X
protected

Definition at line 166 of file code-generator-base.hpp.

◆ ad_Y

template<typename _Scalar >
ADVectorXs pinocchio::CodeGenBase< _Scalar >::ad_Y
protected

Definition at line 166 of file code-generator-base.hpp.

◆ dddq_dq

template<typename _Scalar >
MatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::dddq_dq
protected

Definition at line 604 of file code-generator-algo.hpp.

◆ dddq_dtau

template<typename _Scalar >
MatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::dddq_dtau
protected

Definition at line 604 of file code-generator-algo.hpp.

◆ dddq_dv

template<typename _Scalar >
MatrixXs pinocchio::CodeGenABADerivatives< _Scalar >::dddq_dv
protected

Definition at line 604 of file code-generator-algo.hpp.

◆ partial_derivatives

template<typename _Scalar >
VectorXs pinocchio::CodeGenABADerivatives< _Scalar >::partial_derivatives
protected

Definition at line 602 of file code-generator-algo.hpp.

◆ x

template<typename _Scalar >
VectorXs pinocchio::CodeGenABADerivatives< _Scalar >::x
protected

Definition at line 601 of file code-generator-algo.hpp.

◆ y

template<typename _Scalar >
VectorXs pinocchio::CodeGenBase< _Scalar >::y
protected

Definition at line 172 of file code-generator-base.hpp.


The documentation for this struct was generated from the following file:


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:01