|  | 
| 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 | 
|  | 
| enum | { Options = 0
 } | 
|  | 
| typedef ADModel::ConfigVectorType | ADConfigVectorType | 
|  | 
| typedef pinocchio::DataTpl< ADScalar, Options > | ADData | 
|  | 
| typedef CppAD::ADFun< CGScalar > | ADFun | 
|  | 
| typedef Eigen::Matrix< ADScalar, Eigen::Dynamic, Eigen::Dynamic, Options > | ADMatrixXs | 
|  | 
| typedef pinocchio::ModelTpl< ADScalar, Options > | ADModel | 
|  | 
| typedef CppAD::AD< CGScalar > | ADScalar | 
|  | 
| typedef ADModel::TangentVectorType | ADTangentVectorType | 
|  | 
| typedef Eigen::Matrix< ADScalar, Eigen::Dynamic, 1, Options > | ADVectorXs | 
|  | 
| typedef pinocchio::DataTpl< CGScalar, Options > | CGData | 
|  | 
| typedef pinocchio::ModelTpl< CGScalar, Options > | CGModel | 
|  | 
| typedef CppAD::cg::CG< Scalar > | CGScalar | 
|  | 
| typedef Model::ConfigVectorType | ConfigVectorType | 
|  | 
| typedef pinocchio::DataTpl< Scalar, Options > | Data | 
|  | 
| typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > | MatrixXs | 
|  | 
| typedef pinocchio::ModelTpl< Scalar, Options > | Model | 
|  | 
| 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, Options > | VectorXs | 
|  | 
|  | 
| void | buildMap () | 
|  | build the mapping Y = f(X)  More... 
 | 
|  | 
|  | CodeGenDifference (const Model &model, const std::string &function_name="difference", const std::string &library_name="cg_difference_eval") | 
|  | 
| template<typename ConfigVectorType1 , typename ConfigVectorType2 , typename TangentVector > | 
| void | evalFunction (const Eigen::MatrixBase< ConfigVectorType1 > &q0, const Eigen::MatrixBase< ConfigVectorType2 > &q1, const Eigen::MatrixBase< TangentVector > &v) | 
|  | 
| template<typename Vector > | 
| void | evalFunction (const Eigen::MatrixBase< Vector > &x) | 
|  | 
|  | 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 () | 
|  | 
template<typename _Scalar>
struct pinocchio::CodeGenDifference< _Scalar >
Definition at line 1135 of file code-generator-algo.hpp.