- 3.0.2 models module.
helperFunctions.h
Go to the documentation of this file.
1 /**********************************************************************************************************************
2 This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich.
3 Licensed under the BSD-2 license (see LICENSE file in main directory)
4 **********************************************************************************************************************/
5 
6 
7 #ifndef SRC_HYQ_CODEGEN_HELPERFUNCTIONS_H_
8 #define SRC_HYQ_CODEGEN_HELPERFUNCTIONS_H_
9 
10 #include <ct/core/core.h>
11 #include <ct/rbd/rbd.h>
12 #include <ct/models/HyQ/HyQ.h>
13 
14 namespace ct {
15 namespace models {
16 namespace HyQ {
17 
18 // a floating base forward-dynamic system templated on scalar type
20 
21 template <typename SCALAR>
23 
24 // extract dimensions
27 
28 // shortcut for number of joints
29 const size_t njoints = HyQSystem::Kinematics::NJOINTS;
30 const size_t nEE = HyQSystem::Kinematics::NUM_EE;
31 
32 template <typename SCALAR>
33 Eigen::Matrix<SCALAR, control_dim + 6, 1> hyqInverseDynamics(const Eigen::Matrix<SCALAR, state_dim + 18, 1>& x)
34 {
35  ct::rbd::HyQ::tpl::Dynamics<SCALAR> hyqDynamics;
37 
38  // we assume x contains: q, q_dot, q_ddot
39  hyqState.fromStateVectorEulerXyz(x.template topRows<state_dim>());
40 
41  ct::rbd::tpl::RigidBodyAcceleration<SCALAR> base_a(x.template segment<6>(state_dim));
42  ct::rbd::JointAcceleration<njoints, SCALAR> qdd(x.template bottomRows<njoints>());
43 
44  typename ct::rbd::HyQ::tpl::Dynamics<SCALAR>::ExtLinkForces_t fext(Eigen::Matrix<SCALAR, 6, 1>::Zero()); //zero
45 
46  // output
48  typename ct::rbd::HyQ::tpl::Dynamics<SCALAR>::ForceVector_t base_w;
49 
50  hyqDynamics.FloatingBaseFullyActuatedID(hyqState, base_a, qdd, fext, base_w, u);
51 
52  Eigen::Matrix<SCALAR, control_dim + 6, 1> y;
53  y << base_w, u;
54  return y;
55 }
56 
57 template <typename SCALAR>
58 Eigen::Matrix<SCALAR, nEE * 6, 1> hyqForwardKinematics(const Eigen::Matrix<SCALAR, state_dim, 1>& x)
59 {
60  ct::rbd::HyQ::tpl::Kinematics<SCALAR> hyqKinematics;
62  hyqState.fromStateVectorEulerXyz(x.template topRows<state_dim>());
63 
64  // output vector: positions and velocities for all endeffectors
65  Eigen::Matrix<SCALAR, nEE * 6, 1> y;
66 
67  for (size_t i = 0; i < nEE; i++)
68  {
69  y.template segment<3>(i * 6) =
70  hyqKinematics.getEEPositionInWorld(i, hyqState.basePose(), hyqState.jointPositions()).toImplementation();
71  y.template segment<3>(i * 6 + 3) = hyqKinematics.getEEVelocityInWorld(i, hyqState).toImplementation();
72  }
73 
74  return y;
75 }
76 
77 template <typename SCALAR>
78 Eigen::Matrix<SCALAR, state_dim, 1> hyqContactModelForwardDynamics(
79  const Eigen::Matrix<SCALAR, state_dim + control_dim + 1, 1>& x) // state, input, time
80 {
82  std::shared_ptr<ContactModel<SCALAR>> contactModel =
83  std::shared_ptr<ContactModel<SCALAR>>(new ContactModel<SCALAR>());
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);
89  contactModel->smoothing() = static_cast<typename ContactModel<SCALAR>::VELOCITY_SMOOTHING>(
91 
92  system.setContactModel(contactModel);
94 
95  system.computeControlledDynamics(x.segment(0, state_dim), SCALAR(0.0), x.segment(state_dim, control_dim), y);
96 
97  return y;
98 }
99 }
100 }
101 }
102 
103 
104 #endif /* SRC_HYQ_CODEGEN_HELPERFUNCTIONS_H_ */
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
for i
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