#include <code-generator-base.hpp>
Public Member Functions | |
virtual void | buildMap ()=0 |
build the mapping Y = f(X) More... | |
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) |
Protected Attributes | |
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 |
Definition at line 17 of file code-generator-base.hpp.
typedef ADModel::ConfigVectorType pinocchio::CodeGenBase< _Scalar >::ADConfigVectorType |
Definition at line 41 of file code-generator-base.hpp.
typedef pinocchio::DataTpl<ADScalar,Options> pinocchio::CodeGenBase< _Scalar >::ADData |
Definition at line 30 of file code-generator-base.hpp.
typedef CppAD::ADFun<CGScalar> pinocchio::CodeGenBase< _Scalar >::ADFun |
Definition at line 44 of file code-generator-base.hpp.
typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,Eigen::Dynamic,Options> pinocchio::CodeGenBase< _Scalar >::ADMatrixXs |
Definition at line 36 of file code-generator-base.hpp.
typedef pinocchio::ModelTpl<ADScalar,Options> pinocchio::CodeGenBase< _Scalar >::ADModel |
Definition at line 29 of file code-generator-base.hpp.
typedef CppAD::AD<CGScalar> pinocchio::CodeGenBase< _Scalar >::ADScalar |
Definition at line 21 of file code-generator-base.hpp.
typedef ADModel::TangentVectorType pinocchio::CodeGenBase< _Scalar >::ADTangentVectorType |
Definition at line 42 of file code-generator-base.hpp.
typedef Eigen::Matrix<ADScalar,Eigen::Dynamic,1,Options> pinocchio::CodeGenBase< _Scalar >::ADVectorXs |
Definition at line 35 of file code-generator-base.hpp.
typedef pinocchio::DataTpl<CGScalar,Options> pinocchio::CodeGenBase< _Scalar >::CGData |
Definition at line 28 of file code-generator-base.hpp.
typedef pinocchio::ModelTpl<CGScalar,Options> pinocchio::CodeGenBase< _Scalar >::CGModel |
Definition at line 27 of file code-generator-base.hpp.
typedef CppAD::cg::CG<Scalar> pinocchio::CodeGenBase< _Scalar >::CGScalar |
Definition at line 20 of file code-generator-base.hpp.
typedef Model::ConfigVectorType pinocchio::CodeGenBase< _Scalar >::ConfigVectorType |
Definition at line 38 of file code-generator-base.hpp.
typedef pinocchio::DataTpl<Scalar,Options> pinocchio::CodeGenBase< _Scalar >::Data |
Definition at line 26 of file code-generator-base.hpp.
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options> pinocchio::CodeGenBase< _Scalar >::MatrixXs |
Definition at line 32 of file code-generator-base.hpp.
typedef pinocchio::ModelTpl<Scalar,Options> pinocchio::CodeGenBase< _Scalar >::Model |
Definition at line 25 of file code-generator-base.hpp.
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options|Eigen::RowMajor> pinocchio::CodeGenBase< _Scalar >::RowMatrixXs |
Definition at line 34 of file code-generator-base.hpp.
typedef _Scalar pinocchio::CodeGenBase< _Scalar >::Scalar |
Definition at line 19 of file code-generator-base.hpp.
typedef Model::TangentVectorType pinocchio::CodeGenBase< _Scalar >::TangentVectorType |
Definition at line 39 of file code-generator-base.hpp.
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> pinocchio::CodeGenBase< _Scalar >::VectorXs |
Definition at line 33 of file code-generator-base.hpp.
anonymous enum |
Enumerator | |
---|---|
Options |
Definition at line 23 of file code-generator-base.hpp.
|
inline |
Definition at line 46 of file code-generator-base.hpp.
|
pure virtual |
build the mapping Y = f(X)
Implemented in pinocchio::CodeGenDDifference< _Scalar >, pinocchio::CodeGenDifference< _Scalar >, pinocchio::CodeGenIntegrate< _Scalar >, pinocchio::CodeGenABADerivatives< _Scalar >, pinocchio::CodeGenRNEADerivatives< _Scalar >, pinocchio::CodeGenMinv< _Scalar >, pinocchio::CodeGenCRBA< _Scalar >, pinocchio::CodeGenABA< _Scalar >, and pinocchio::CodeGenRNEA< _Scalar >.
|
inline |
Definition at line 83 of file code-generator-base.hpp.
|
inline |
Definition at line 86 of file code-generator-base.hpp.
|
inline |
Definition at line 122 of file code-generator-base.hpp.
|
inline |
Definition at line 130 of file code-generator-base.hpp.
|
inline |
Definition at line 95 of file code-generator-base.hpp.
|
inline |
Dimension of the input vector.
Definition at line 140 of file code-generator-base.hpp.
|
inline |
Dimension of the output vector.
Definition at line 142 of file code-generator-base.hpp.
|
inline |
Definition at line 69 of file code-generator-base.hpp.
|
inline |
Definition at line 102 of file code-generator-base.hpp.
|
protected |
Definition at line 164 of file code-generator-base.hpp.
|
protected |
Definition at line 147 of file code-generator-base.hpp.
|
protected |
Definition at line 164 of file code-generator-base.hpp.
|
protected |
Definition at line 161 of file code-generator-base.hpp.
|
protected |
Definition at line 146 of file code-generator-base.hpp.
|
protected |
Definition at line 163 of file code-generator-base.hpp.
|
protected |
Definition at line 163 of file code-generator-base.hpp.
|
protected |
Definition at line 164 of file code-generator-base.hpp.
|
protected |
Definition at line 160 of file code-generator-base.hpp.
|
protected |
Definition at line 160 of file code-generator-base.hpp.
|
protected |
Options to generate or not the source code for the evaluation function.
Definition at line 155 of file code-generator-base.hpp.
|
protected |
Options to build or not the Jacobian of he function.
Definition at line 158 of file code-generator-base.hpp.
|
protected |
Definition at line 169 of file code-generator-base.hpp.
|
protected |
Definition at line 172 of file code-generator-base.hpp.
|
protected |
Definition at line 171 of file code-generator-base.hpp.
|
protected |
Name of the function.
Definition at line 150 of file code-generator-base.hpp.
|
protected |
Definition at line 173 of file code-generator-base.hpp.
|
protected |
Definition at line 167 of file code-generator-base.hpp.
|
protected |
Definition at line 170 of file code-generator-base.hpp.
|
protected |
Name of the library.
Definition at line 152 of file code-generator-base.hpp.
|
protected |
Definition at line 166 of file code-generator-base.hpp.