#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 | compileAndLoadLib (const std::string &gcc_path) | 
| void | compileLib (const std::string &gcc_path="/usr/bin/gcc", const std::string &compile_options="-Ofast") | 
| 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, const std::string &gcc_path="/usr/bin/gcc", const std::string &compile_options="-Ofast") | 
| virtual | ~CodeGenBase () | 
| 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 45 of file code-generator-base.hpp.
| typedef pinocchio::DataTpl<ADScalar, Options> pinocchio::CodeGenBase< _Scalar >::ADData | 
Definition at line 33 of file code-generator-base.hpp.
| typedef CppAD::ADFun<CGScalar> pinocchio::CodeGenBase< _Scalar >::ADFun | 
Definition at line 48 of file code-generator-base.hpp.
| typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, Eigen::Dynamic, Options> pinocchio::CodeGenBase< _Scalar >::ADMatrixXs | 
Definition at line 40 of file code-generator-base.hpp.
| typedef pinocchio::ModelTpl<ADScalar, Options> pinocchio::CodeGenBase< _Scalar >::ADModel | 
Definition at line 32 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 46 of file code-generator-base.hpp.
| typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1, Options> pinocchio::CodeGenBase< _Scalar >::ADVectorXs | 
Definition at line 39 of file code-generator-base.hpp.
| typedef pinocchio::DataTpl<CGScalar, Options> pinocchio::CodeGenBase< _Scalar >::CGData | 
Definition at line 31 of file code-generator-base.hpp.
| typedef pinocchio::ModelTpl<CGScalar, Options> pinocchio::CodeGenBase< _Scalar >::CGModel | 
Definition at line 30 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 42 of file code-generator-base.hpp.
| typedef pinocchio::DataTpl<Scalar, Options> pinocchio::CodeGenBase< _Scalar >::Data | 
Definition at line 29 of file code-generator-base.hpp.
| typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> pinocchio::CodeGenBase< _Scalar >::MatrixXs | 
Definition at line 35 of file code-generator-base.hpp.
| typedef pinocchio::ModelTpl<Scalar, Options> pinocchio::CodeGenBase< _Scalar >::Model | 
Definition at line 28 of file code-generator-base.hpp.
| typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options | Eigen::RowMajor> pinocchio::CodeGenBase< _Scalar >::RowMatrixXs | 
Definition at line 38 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 43 of file code-generator-base.hpp.
| typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> pinocchio::CodeGenBase< _Scalar >::VectorXs | 
Definition at line 36 of file code-generator-base.hpp.
| anonymous enum | 
| Enumerator | |
|---|---|
| Options | |
Definition at line 23 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 50 of file code-generator-base.hpp.
| 
 | inlinevirtual | 
Definition at line 71 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::CodeGenConstraintDynamics< _Scalar >, pinocchio::CodeGenConstraintDynamicsDerivatives< _Scalar >, pinocchio::CodeGenABADerivatives< _Scalar >, pinocchio::CodeGenRNEADerivatives< _Scalar >, pinocchio::CodeGenMinv< _Scalar >, pinocchio::CodeGenCRBA< _Scalar >, pinocchio::CodeGenABA< _Scalar >, and pinocchio::CodeGenRNEA< _Scalar >.
| 
 | inline | 
Definition at line 94 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 117 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 99 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 151 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 159 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 109 of file code-generator-base.hpp.
| 
 | inline | 
Dimension of the input vector.
Definition at line 170 of file code-generator-base.hpp.
| 
 | inline | 
Dimension of the output vector.
Definition at line 175 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 78 of file code-generator-base.hpp.
| 
 | inline | 
Definition at line 123 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 199 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 182 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 199 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 196 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 181 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 198 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 198 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 199 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 195 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 195 of file code-generator-base.hpp.
| 
 | protected | 
Options to generate or not the source code for the evaluation function.
Definition at line 190 of file code-generator-base.hpp.
| 
 | protected | 
Options to build or not the Jacobian of he function.
Definition at line 193 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 204 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 207 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 206 of file code-generator-base.hpp.
| 
 | protected | 
Name of the function.
Definition at line 185 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 208 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 202 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 205 of file code-generator-base.hpp.
| 
 | protected | 
Name of the library.
Definition at line 187 of file code-generator-base.hpp.
| 
 | protected | 
Definition at line 201 of file code-generator-base.hpp.