- 3.0.2 models module.
|
#include <ct/optcon/optcon.h>
#include <ct/rbd/rbd.h>
#include <ct/models/HyQ/HyQ.h>
#include <ct/models/CodegenOutputDirs.h>
#include "helperFunctions.h"
Typedefs | |
typedef CppAD::AD< CppAD::cg::CG< double > > | SCALAR |
typedef SCALAR::value_type | AD_ValueType |
typedef ct::rbd::FloatingBaseFDSystem< ct::rbd::HyQ::tpl::Dynamics< SCALAR >, false > | HyQSystemAD |
Functions | |
void | generateInverseDynamics () |
void | generateForwardKinematics () |
void | generateForwardZeroForwardDynamics () |
void | generateFDLinearization (int argc, char *argv[]) |
int | main (int argc, char *argv[]) |
Variables | |
const size_t | state_dim = HyQSystemAD::STATE_DIM |
const size_t | control_dim = HyQSystemAD::CONTROL_DIM |
typedef CppAD::AD<CppAD::cg::CG<double> > SCALAR |
typedef SCALAR::value_type AD_ValueType |
typedef ct::rbd::FloatingBaseFDSystem<ct::rbd::HyQ::tpl::Dynamics<SCALAR>, false> HyQSystemAD |
void generateInverseDynamics | ( | ) |
Referenced by main().
void generateForwardKinematics | ( | ) |
Referenced by main().
void generateForwardZeroForwardDynamics | ( | ) |
Referenced by main().
void generateFDLinearization | ( | int | argc, |
char * | argv[] | ||
) |
Referenced by main().
int main | ( | int | argc, |
char * | argv[] | ||
) |
const size_t state_dim = HyQSystemAD::STATE_DIM |
const size_t control_dim = HyQSystemAD::CONTROL_DIM |