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

#include <code-generator-algo.hpp>

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

Public Types

typedef Base::ADConfigVectorType ADConfigVectorType
 
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...
 
 CodeGenRNEA (const Model &model, const std::string &function_name="rnea", const std::string &library_name="cg_rnea_eval")
 
template<typename ConfigVectorType , typename TangentVector1 , typename TangentVector2 >
void evalFunction (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
 
template<typename ConfigVectorType , typename TangentVector1 , typename TangentVector2 >
void evalJacobian (const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
 
- 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 compileLib ()
 
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)
 

Public Attributes

MatrixXs dtau_da
 
MatrixXs dtau_dq
 
MatrixXs dtau_dv
 

Protected Attributes

ADTangentVectorType ad_a
 
ADTangentVectorType ad_dq
 
ADConfigVectorType ad_q
 
ADConfigVectorType ad_q_plus
 
ADTangentVectorType ad_v
 
VectorXs res
 
VectorXs x
 
- 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::CodeGenRNEA< _Scalar >

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

Member Typedef Documentation

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

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

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

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

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

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

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

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

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

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

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

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

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

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

Constructor & Destructor Documentation

template<typename _Scalar>
pinocchio::CodeGenRNEA< _Scalar >::CodeGenRNEA ( const Model model,
const std::string &  function_name = "rnea",
const std::string &  library_name = "cg_rnea_eval" 
)
inline

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

Member Function Documentation

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

build the mapping Y = f(X)

Implements pinocchio::CodeGenBase< _Scalar >.

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

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

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

template<typename _Scalar>
template<typename ConfigVectorType , typename TangentVector1 , typename TangentVector2 >
void pinocchio::CodeGenRNEA< _Scalar >::evalJacobian ( const Eigen::MatrixBase< ConfigVectorType > &  q,
const Eigen::MatrixBase< TangentVector1 > &  v,
const Eigen::MatrixBase< TangentVector2 > &  a 
)
inline

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

Member Data Documentation

template<typename _Scalar>
ADTangentVectorType pinocchio::CodeGenRNEA< _Scalar >::ad_a
protected

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

template<typename _Scalar>
ADTangentVectorType pinocchio::CodeGenRNEA< _Scalar >::ad_dq
protected

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

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

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

template<typename _Scalar>
ADConfigVectorType pinocchio::CodeGenRNEA< _Scalar >::ad_q_plus
protected

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

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

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

template<typename _Scalar>
MatrixXs pinocchio::CodeGenRNEA< _Scalar >::dtau_da

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

template<typename _Scalar>
MatrixXs pinocchio::CodeGenRNEA< _Scalar >::dtau_dq

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

template<typename _Scalar>
MatrixXs pinocchio::CodeGenRNEA< _Scalar >::dtau_dv

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

template<typename _Scalar>
VectorXs pinocchio::CodeGenRNEA< _Scalar >::res
protected

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

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

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


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


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05