- 3.0.2 models module.
HyALinearizationCodeGen.cpp File Reference
#include <ct/core/core.h>
#include <ct/optcon/optcon.h>
#include <ct/rbd/rbd.h>
#include <cmath>
#include <memory>
#include <ct/models/HyA/HyA.h>
#include <ct/rbd/systems/FixBaseFDSystem.h>
#include <ct/models/CodegenOutputDirs.h>

Typedefs

typedef ct::core::ADCodegenLinearizer< state_dim, control_dim >::ADCGScalar Scalar
 
typedef ct::rbd::FixBaseFDSystem< ct::rbd::HyA::tpl::Dynamics< Scalar > > HyANonLinearSystem
 
typedef ct::core::DerivativesCppadCG< state_dim, control_dimJacCG
 
template<typename SCALAR >
using control_vector_t = typename ct::rbd::HyA::tpl::Dynamics< SCALAR >::control_vector_t
 
template<typename SCALAR >
using ExtLinkForces_t = typename ct::rbd::HyA::tpl::Dynamics< SCALAR >::ExtLinkForces_t
 

Functions

template<typename SCALAR >
Eigen::Matrix< SCALAR, control_dim, 1 > hyaInverseDynamics (const Eigen::Matrix< SCALAR, state_dim, 1 > &x)
 
int main (int argc, char **argv)
 

Variables

const size_t state_dim = ct::rbd::FixBaseFDSystem<ct::rbd::HyA::Dynamics>::STATE_DIM
 
const size_t control_dim = ct::rbd::FixBaseFDSystem<ct::rbd::HyA::Dynamics>::CONTROL_DIM
 
const size_t njoints = ct::rbd::HyA::Dynamics::NJOINTS
 

Typedef Documentation

◆ Scalar

typedef ct::core::ADCodegenLinearizer<state_dim, control_dim>::ADCGScalar Scalar

◆ HyANonLinearSystem

◆ JacCG

typedef ct::core::DerivativesCppadCG<state_dim, control_dim> JacCG

◆ control_vector_t

template<typename SCALAR >
using control_vector_t = typename ct::rbd::HyA::tpl::Dynamics<SCALAR>::control_vector_t

◆ ExtLinkForces_t

template<typename SCALAR >
using ExtLinkForces_t = typename ct::rbd::HyA::tpl::Dynamics<SCALAR>::ExtLinkForces_t

Function Documentation

◆ hyaInverseDynamics()

template<typename SCALAR >
Eigen::Matrix<SCALAR, control_dim, 1> hyaInverseDynamics ( const Eigen::Matrix< SCALAR, state_dim, 1 > &  x)

◆ main()

int main ( int  argc,
char **  argv 
)

Variable Documentation

◆ state_dim

const size_t state_dim = ct::rbd::FixBaseFDSystem<ct::rbd::HyA::Dynamics>::STATE_DIM

◆ control_dim

const size_t control_dim = ct::rbd::FixBaseFDSystem<ct::rbd::HyA::Dynamics>::CONTROL_DIM

◆ njoints

const size_t njoints = ct::rbd::HyA::Dynamics::NJOINTS