Cheetah Software  1.0
DynamicsSimulator.cpp
Go to the documentation of this file.
1 
12 
16 template <typename T>
18  bool useSpringDamper)
19  : _model(model), _useSpringDamper(useSpringDamper) {
20  if (_useSpringDamper) {
22  } else {
24  }
25 
26  _state.bodyVelocity = SVec<T>::Zero();
27  _state.bodyPosition = Vec3<T>::Zero();
28  _state.bodyOrientation = Quat<T>::Zero();
29  _state.q = DVec<T>::Zero(_model._nDof - 6);
30  _state.qd = DVec<T>::Zero(_model._nDof - 6);
31  _dstate.qdd = DVec<T>::Zero(_model._nDof - 6);
32  _lastBodyVelocity.setZero();
33 }
34 
40 template <typename T>
41 void DynamicsSimulator<T>::step(T dt, const DVec<T> &tau, T kp, T kd ) {
42  // fwd-kin on gc points
43  // compute ground contact forces
44  // aba
45  // integrate
46  forwardKinematics(); // compute forward kinematics
47  updateCollisions(dt, kp, kd); // process collisions
48  // Process Homing
49  if( _homing.active_flag) {
50 
51  Mat3<T> R10_des = rpyToRotMat(_homing.rpy); // R10_des
52  Mat3<T> R10_act = _model.getOrientation(5).transpose(); // R10
53  Mat3<T> eR01 = R10_des.transpose()*R10_act; // eR * R01 = R01_des
54 
55  Vec4<T> equat = rotationMatrixToQuaternion(eR01.transpose());
56  Vec3<T> angle_axis = quatToso3(equat); // in world frame
57 
58  Vec3<T> p = _model.getPosition(5);
59  Vec3<T> f = _homing.kp_lin*(_homing.position - p)-_homing.kd_lin*_model.getLinearVelocity(5);
60 
61  // Note: External forces are spatial forces in the {0} frame.
62  _model._externalForces.at(5) += forceToSpatialForce(f,p);
63  _model._externalForces.at(5).head(3) += _homing.kp_ang*angle_axis - _homing.kd_ang*_model.getAngularVelocity(5);
64 
65  }
66 
67 
68  runABA(tau); // dynamics algorithm
69  integrate(dt); // step forward
70 
71  _model.setState(_state);
72  _model.resetExternalForces(); // clear external forces
73  _model.resetCalculationFlags();
74 }
75 
76 template <typename T>
78  _model.forwardKinematics();
79  _contact_constr->UpdateExternalForces(kp, kd, dt);
80 }
81 
86 template <typename T>
88  if (_useSpringDamper) {
89  Vec3<T> omegaBody = _state.bodyVelocity.template block<3, 1>(0, 0);
91  _state.bodyPosition);
93  Vec3<T> omega0 = R.transpose() * omegaBody;
94 
95  // actual integration
96  _state.qd += _dstate.qdd * dt;
97  _state.q += _state.qd * dt;
98 
99  _state.bodyVelocity += _dstate.dBodyVelocity * dt;
100  _state.bodyPosition += _dstate.dBodyPosition * dt;
101  _state.bodyOrientation = integrateQuat(_state.bodyOrientation, omega0, dt);
102  } else {
103  // actual integration
104  // Velocity Update by integrating acceleration
105  _state.qd += _dstate.qdd * dt;
106  _state.bodyVelocity += _dstate.dBodyVelocity * dt;
107 
108  // Contact Constraint Velocity Updated
109  _contact_constr->UpdateQdot(_state);
110 
111  // Prepare body velocity integration
112  RotMat<T> R_body = quaternionToRotationMatrix(_state.bodyOrientation);
113 
114  _dstate.dBodyPosition =
115  R_body.transpose() * _state.bodyVelocity.template block<3, 1>(3, 0);
116  Vec3<T> omegaBody = _state.bodyVelocity.template block<3, 1>(0, 0);
117 
118  // Position Update
119  _state.q += _state.qd * dt;
120  _state.bodyPosition += _dstate.dBodyPosition * dt;
121  _state.bodyOrientation =
122  integrateQuatImplicit(_state.bodyOrientation, omegaBody, dt);
123  _dstate.dBodyVelocity = (_state.bodyVelocity - _lastBodyVelocity) / dt;
124  _lastBodyVelocity = _state.bodyVelocity;
125  }
126 }
127 
128 template class DynamicsSimulator<double>;
129 
130 template class DynamicsSimulator<float>;
auto forceToSpatialForce(const Eigen::MatrixBase< T > &f, const Eigen::MatrixBase< T2 > &p)
Definition: spatial.h:348
Quat< typename T::Scalar > integrateQuatImplicit(const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DynamicsSimulator(FloatingBaseModel< T > &model, bool useSpringDamper=false)
void forwardKinematics()
Do forward kinematics for feet.
Mat3< typename T::Scalar > rpyToRotMat(const Eigen::MatrixBase< T > &v)
Spring Damper based Contact Computation logic.
typename Eigen::Matrix< T, 6, 6 > Mat6
Definition: cppTypes.h:70
typename Eigen::Matrix< T, 3, 3 > Mat3
Definition: cppTypes.h:54
typename Eigen::Matrix< T, 4, 1 > Quat
Definition: cppTypes.h:58
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
FBModelStateDerivative< T > _dstate
void integrate(T dt)
Integrate to find new _state.
typename Eigen::Matrix< T, 6, 1 > SVec
Definition: cppTypes.h:62
Quat< typename T::Scalar > integrateQuat(const Eigen::MatrixBase< T > &quat, const Eigen::MatrixBase< T2 > &omega, T3 dt)
void updateCollisions(T dt, T kp, T kd)
auto createSXform(const Eigen::MatrixBase< T > &R, const Eigen::MatrixBase< T2 > &r)
Definition: spatial.h:140
RobotHomingInfo< T > _homing
ContactConstraint< T > * _contact_constr
Quat< typename T::Scalar > rotationMatrixToQuaternion(const Eigen::MatrixBase< T > &r1)
typename Eigen::Matrix< T, 4, 1 > Vec4
Definition: cppTypes.h:30
void step(T dt, const DVec< T > &tau, T kp, T kd)
Initialize simulator with given model.
void runABA(const DVec< T > &tau)
Simulate forward one step.
Vec3< typename T::Scalar > quatToso3(const Eigen::MatrixBase< T > &q)
typename Eigen::Matrix< T, Eigen::Dynamic, 1 > DVec
Definition: cppTypes.h:102
FloatingBaseModel< T > & _model
FBModelState< T > _state
Update ground collision list.
Rigid Body Dynamics Simulator with Collisions.
Mat3< typename T::Scalar > quaternionToRotationMatrix(const Eigen::MatrixBase< T > &q)
typename Eigen::Matrix< T, 3, 3 > RotMat
Definition: cppTypes.h:18
auto rotationFromSXform(const Eigen::MatrixBase< T > &X)
Definition: spatial.h:157
MX f(const MX &x, const MX &u)