19 : _model(model), _useSpringDamper(useSpringDamper) {
53 Mat3<T> eR01 = R10_des.transpose()*R10_act;
72 _model.resetExternalForces();
73 _model.resetCalculationFlags();
78 _model.forwardKinematics();
89 Vec3<T> omegaBody =
_state.bodyVelocity.template block<3, 1>(0, 0);
93 Vec3<T> omega0 = R.transpose() * omegaBody;
115 R_body.transpose() *
_state.bodyVelocity.template block<3, 1>(3, 0);
116 Vec3<T> omegaBody =
_state.bodyVelocity.template block<3, 1>(0, 0);
auto forceToSpatialForce(const Eigen::MatrixBase< T > &f, const Eigen::MatrixBase< T2 > &p)
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)
typename Eigen::Matrix< T, 6, 6 > Mat6
typename Eigen::Matrix< T, 3, 3 > Mat3
typename Eigen::Matrix< T, 4, 1 > Quat
typename Eigen::Matrix< T, 3, 1 > Vec3
FBModelStateDerivative< T > _dstate
void integrate(T dt)
Integrate to find new _state.
typename Eigen::Matrix< T, 6, 1 > SVec
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)
RobotHomingInfo< T > _homing
ContactConstraint< T > * _contact_constr
Quat< typename T::Scalar > rotationMatrixToQuaternion(const Eigen::MatrixBase< T > &r1)
typename Eigen::Matrix< T, 4, 1 > Vec4
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)
SVec< T > _lastBodyVelocity
typename Eigen::Matrix< T, Eigen::Dynamic, 1 > DVec
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
auto rotationFromSXform(const Eigen::MatrixBase< T > &X)
MX f(const MX &x, const MX &u)