Template Struct AutoDiffABA

Inheritance Relationships

Base Type

Struct Documentation

template<typename _Scalar>
struct AutoDiffABA : public pinocchio::casadi::AutoDiffAlgoBase<_Scalar>

Public Types

typedef AutoDiffAlgoBase<_Scalar> Base
typedef Base::Scalar Scalar
typedef Base::TangentVectorType TangentVectorType
typedef Base::RowMatrixXs RowMatrixXs
typedef Base::VectorXs VectorXs
typedef Base::MatrixXs MatrixXs
typedef Base::ADFun ADFun
typedef Base::DMVector DMVector
typedef Base::DMMatrix DMMatrix
typedef Base::ADScalar ADScalar
typedef Base::ADSVector ADSVector
typedef Base::ADConfigVectorType ADConfigVectorType
typedef Base::ADTangentVectorType ADTangentVectorType

Public Functions

inline explicit AutoDiffABA(const Model &model, const std::string &filename = "casadi_aba", const std::string &libname = "libcasadi_cg_aba", const std::string &fun_name = "eval_f")
inline virtual ~AutoDiffABA()
inline virtual void buildMap()

build the mapping Y = f(X)

template<typename ConfigVectorType1, typename TangentVectorType1, typename TangentVectorType2>
inline void evalFunction(const Eigen::MatrixBase<ConfigVectorType1> &q, const Eigen::MatrixBase<TangentVectorType1> &v, const Eigen::MatrixBase<TangentVectorType2> &tau)
template<typename ConfigVectorType1, typename TangentVectorType1, typename TangentVectorType2>
inline void evalJacobian(const Eigen::MatrixBase<ConfigVectorType1> &q, const Eigen::MatrixBase<TangentVectorType1> &v, const Eigen::MatrixBase<TangentVectorType2> &tau)

Public Members

TangentVectorType ddq
RowMatrixXs ddq_dq
RowMatrixXs ddq_dv
RowMatrixXs ddq_dtau

Protected Attributes

ADScalar cs_q
ADScalar cs_v
ADScalar cs_tau
ADScalar cs_v_int
ADScalar cs_ddq
ADScalar cs_ddq_dq
ADScalar cs_ddq_dv
ADScalar cs_ddq_dtau
ADConfigVectorType q_ad
ADConfigVectorType q_int_ad
ADTangentVectorType v_ad
ADTangentVectorType v_int_ad
ADTangentVectorType tau_ad
std::vector<Scalar> q_vec
std::vector<Scalar> v_vec
std::vector<Scalar> v_int_vec
std::vector<Scalar> tau_vec
ADData ad_data
ADModel ad_model
::casadi::CodeGenerator cg_generated
std::string filename
std::string fun_name
std::string libname
ADFun ad_fun
ADFun ad_fun_derivs
ADFun fun
ADFun fun_derivs
std::vector<DMMatrix> fun_output
std::vector<DMMatrix> fun_output_derivs