7 #ifndef SRC_HYQ_CODEGEN_HELPERFUNCTIONS_H_ 8 #define SRC_HYQ_CODEGEN_HELPERFUNCTIONS_H_ 21 template <
typename SCALAR>
29 const size_t njoints = HyQSystem::Kinematics::NJOINTS;
30 const size_t nEE = HyQSystem::Kinematics::NUM_EE;
32 template <
typename SCALAR>
33 Eigen::Matrix<SCALAR, control_dim + 6, 1>
hyqInverseDynamics(
const Eigen::Matrix<SCALAR, state_dim + 18, 1>& x)
35 ct::rbd::HyQ::tpl::Dynamics<SCALAR> hyqDynamics;
48 typename ct::rbd::HyQ::tpl::Dynamics<SCALAR>::ForceVector_t base_w;
50 hyqDynamics.FloatingBaseFullyActuatedID(hyqState, base_a, qdd, fext, base_w, u);
52 Eigen::Matrix<SCALAR, control_dim + 6, 1> y;
57 template <
typename SCALAR>
60 ct::rbd::HyQ::tpl::Kinematics<SCALAR> hyqKinematics;
65 Eigen::Matrix<SCALAR, nEE * 6, 1> y;
67 for (
size_t i = 0;
i <
nEE;
i++)
69 y.template segment<3>(
i * 6) =
71 y.template segment<3>(
i * 6 + 3) = hyqKinematics.getEEVelocityInWorld(
i, hyqState).toImplementation();
77 template <
typename SCALAR>
79 const Eigen::Matrix<SCALAR, state_dim + control_dim + 1, 1>& x)
82 std::shared_ptr<ContactModel<SCALAR>> contactModel =
84 contactModel->k() =
SCALAR(5000);
85 contactModel->d() =
SCALAR(1000);
86 contactModel->alpha() =
SCALAR(100);
87 contactModel->alpha_n() =
SCALAR(100);
88 contactModel->zOffset() =
SCALAR(-0.02);
95 system.computeControlledDynamics(x.segment(0, state_dim),
SCALAR(0.0), x.segment(state_dim, control_dim), y);
const size_t njoints
Definition: helperFunctions.h:29
static const size_t CONTROL_DIM
RigidBodyPose_t & basePose()
JointState< NJOINTS, SCALAR >::JointPositionBlock jointPositions()
ct::core::ControlVector< control_dim > u
void setContactModel(const std::shared_ptr< ContactModel > &contactModel)
CppAD::AD< CppAD::cg::CG< double > > SCALAR
Definition: HyQLinearizationCodegen.cpp:14
ct::rbd::FloatingBaseFDSystem< ct::rbd::HyQ::tpl::Dynamics< double >, false > HyQSystem
Definition: helperFunctions.h:19
typename ct::rbd::HyA::tpl::Dynamics< SCALAR >::ExtLinkForces_t ExtLinkForces_t
Definition: HyALinearizationCodeGen.cpp:31
Eigen::Matrix< SCALAR, control_dim+6, 1 > hyqInverseDynamics(const Eigen::Matrix< SCALAR, state_dim+18, 1 > &x)
Definition: helperFunctions.h:33
static const size_t STATE_DIM
void fromStateVectorEulerXyz(const state_vector_euler_t &state)
const size_t control_dim
Definition: helperFunctions.h:26
const size_t nEE
Definition: helperFunctions.h:30
Eigen::Matrix< SCALAR, state_dim, 1 > hyqContactModelForwardDynamics(const Eigen::Matrix< SCALAR, state_dim+control_dim+1, 1 > &x)
Definition: helperFunctions.h:78
const size_t state_dim
Definition: helperFunctions.h:25
Eigen::Matrix< SCALAR, nEE *6, 1 > hyqForwardKinematics(const Eigen::Matrix< SCALAR, state_dim, 1 > &x)
Definition: helperFunctions.h:58