Template Struct CodeGenBase

Inheritance Relationships

Derived Types

Struct Documentation

template<typename _Scalar>
struct CodeGenBase

Subclassed by pinocchio::CodeGenABA< _Scalar >, pinocchio::CodeGenABADerivatives< _Scalar >, pinocchio::CodeGenCRBA< _Scalar >, pinocchio::CodeGenDDifference< _Scalar >, pinocchio::CodeGenDifference< _Scalar >, pinocchio::CodeGenIntegrate< _Scalar >, pinocchio::CodeGenMinv< _Scalar >, pinocchio::CodeGenRNEA< _Scalar >, pinocchio::CodeGenRNEADerivatives< _Scalar >

Public Types

Values:

enumerator Options
typedef _Scalar Scalar
typedef CppAD::cg::CG<Scalar> CGScalar
typedef CppAD::AD<CGScalar> ADScalar
typedef pinocchio::ModelTpl<Scalar, Options> Model
typedef pinocchio::DataTpl<Scalar, Options> Data
typedef pinocchio::ModelTpl<CGScalar, Options> CGModel
typedef pinocchio::DataTpl<CGScalar, Options> CGData
typedef pinocchio::ModelTpl<ADScalar, Options> ADModel
typedef pinocchio::DataTpl<ADScalar, Options> ADData
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> MatrixXs
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options | Eigen::RowMajor> RowMatrixXs
typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1, Options> ADVectorXs
typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, Eigen::Dynamic, Options> ADMatrixXs
typedef Model::ConfigVectorType ConfigVectorType
typedef Model::TangentVectorType TangentVectorType
typedef ADModel::ConfigVectorType ADConfigVectorType
typedef ADModel::TangentVectorType ADTangentVectorType
typedef CppAD::ADFun<CGScalar> ADFun

Public Functions

inline CodeGenBase(const Model &model, const Eigen::DenseIndex dim_input, const Eigen::DenseIndex dim_output, const std::string &function_name, const std::string &library_name)
virtual void buildMap() = 0

build the mapping Y = f(X)

inline void initLib()
inline CppAD::cg::ModelCSourceGen<Scalar> &codeGenerator()
inline void compileLib(const std::string &gccPath = "/usr/bin/gcc")
inline bool existLib() const
inline void compileAndLoadLib(const std::string &gccPath)
inline void loadLib(const bool generate_if_not_exist = true)
template<typename Vector>
inline void evalFunction(const Eigen::MatrixBase<Vector> &x)
template<typename Vector>
inline void evalJacobian(const Eigen::MatrixBase<Vector> &x)
inline Eigen::DenseIndex getInputDimension() const

Dimension of the input vector.

inline Eigen::DenseIndex getOutputDimension() const

Dimension of the output vector.

Protected Attributes

ADModel ad_model
ADData ad_data
const std::string function_name

Name of the function.

const std::string library_name

Name of the library.

bool build_forward

Options to generate or not the source code for the evaluation function.

bool build_jacobian

Options to build or not the Jacobian of he function.

ADVectorXs ad_X
ADVectorXs ad_Y
ADFun ad_fun
ADConfigVectorType ad_q
ADConfigVectorType ad_q_plus
ADTangentVectorType ad_dq
ADTangentVectorType ad_v
ADTangentVectorType ad_a
VectorXs y
RowMatrixXs jac
std::unique_ptr<CppAD::cg::ModelCSourceGen<Scalar>> cgen_ptr
std::unique_ptr<CppAD::cg::ModelLibraryCSourceGen<Scalar>> libcgen_ptr
std::unique_ptr<CppAD::cg::DynamicModelLibraryProcessor<Scalar>> dynamicLibManager_ptr
std::unique_ptr<CppAD::cg::DynamicLib<Scalar>> dynamicLib_ptr
std::unique_ptr<CppAD::cg::GenericModel<Scalar>> generatedFun_ptr