41 const Vec3<T> &force_ics_at_contact,
44 updateArticulatedBodies();
45 updateForcePropagators();
48 size_t i_opsp = _gcParent.at(gc_index);
54 Mat3<T> Rai = _Xa[i].template block<3, 3>(0, 0).transpose();
59 SVec<T> F = Xc.transpose().template rightCols<3>() * force_ics_at_contact;
67 LambdaInv += tmp * tmp / _d[i];
68 dstate_out.tail(_nDof - 6) += _qdd_from_subqdd.col(i - 6) * tmp / _d[i];
75 F = _ChiUp[i].transpose() * F;
79 dstate_out.head(6) = _invIA5.solve(F);
80 LambdaInv += F.dot(dstate_out.head(6));
81 dstate_out.tail(_nDof - 6) += _qdd_from_base_accel * dstate_out.head(6);
99 if (_qddEffectsUpToDate)
return;
100 updateForcePropagators();
101 _qdd_from_base_accel.setZero();
102 _qdd_from_subqdd.setZero();
110 for (
size_t i = 6; i < _nDof; i++) {
111 _qdd_from_subqdd(i - 6, i - 6) = 1;
112 SVec<T> F = (_ChiUp[i].transpose() - _Xup[i].transpose()) * _S[i];
113 size_t j = _parents[i];
115 _qdd_from_subqdd(i - 6, j - 6) = _S[j].dot(F);
116 F = _ChiUp[j].transpose() * F;
119 _qdd_from_base_accel.row(i - 6) = F.transpose();
121 _qddEffectsUpToDate =
true;
128 template <
typename T>
130 if (_forcePropagatorsUpToDate)
return;
131 updateArticulatedBodies();
132 for (
size_t i = 6; i < _nDof; i++) {
133 _ChiUp[i] = _Xup[i] - _S[i] * _Utot[i].transpose() / _d[i];
135 _forcePropagatorsUpToDate =
true;
141 template <
typename T>
143 if (_articulatedBodiesUpToDate)
return;
147 _IA[5] = _Ibody[5].getMatrix();
150 for (
size_t i = 6; i < _nDof; i++) {
151 _IA[i] = _Ibody[i].getMatrix();
153 _state.q[i - 6] * _gearRatios[i]);
154 _Xuprot[i] = XJrot * _Xrot[i];
155 _Srot[i] = _S[i] * _gearRatios[i];
159 for (
size_t i = _nDof - 1; i >= 6; i--) {
160 _U[i] = _IA[i] * _S[i];
161 _Urot[i] = _Irot[i].getMatrix() * _Srot[i];
162 _Utot[i] = _Xup[i].transpose() * _U[i] + _Xuprot[i].transpose() * _Urot[i];
164 _d[i] = _Srot[i].transpose() * _Urot[i];
165 _d[i] += _S[i].transpose() * _U[i];
168 Mat6<T> Ia = _Xup[i].transpose() * _IA[i] * _Xup[i] +
169 _Xuprot[i].transpose() * _Irot[i].getMatrix() * _Xuprot[i] -
170 _Utot[i] * _Utot[i].transpose() / _d[i];
171 _IA[_parents[i]] += Ia;
174 _invIA5.compute(_IA[5]);
175 _articulatedBodiesUpToDate =
true;
184 template <
typename T>
186 if (count != 1 && count != 6) {
187 throw std::runtime_error(
188 "addDynamicsVars must be called with count=1 (joint) or count=6 " 197 for (
int i = 0; i < count; i++) {
199 _vrot.push_back(zero6);
201 _arot.push_back(zero6);
202 _avp.push_back(zero6);
203 _avprot.push_back(zero6);
205 _crot.push_back(zero6);
207 _Srot.push_back(zero6);
209 _frot.push_back(zero6);
210 _fvp.push_back(zero6);
211 _fvprot.push_back(zero6);
212 _ag.push_back(zero6);
213 _agrot.push_back(zero6);
214 _IC.push_back(zeroInertia);
215 _Xup.push_back(eye6);
216 _Xuprot.push_back(eye6);
219 _ChiUp.push_back(eye6);
225 _Urot.push_back(zero6);
226 _Utot.push_back(zero6);
227 _pA.push_back(zero6);
228 _pArot.push_back(zero6);
229 _externalForces.push_back(zero6);
235 resizeSystemMatricies();
241 template <
typename T>
243 _H.setZero(_nDof, _nDof);
244 _C.setZero(_nDof, _nDof);
247 for (
size_t i = 0; i < _J.size(); i++) {
248 _J[i].setZero(6, _nDof);
252 for (
size_t i = 0; i < _Jc.size(); i++) {
253 _Jc[i].setZero(3, _nDof);
256 _qdd_from_subqdd.resize(_nDof - 6, _nDof - 6);
257 _qdd_from_base_accel.resize(_nDof - 6, 6);
266 template <
typename T>
269 throw std::runtime_error(
"Cannot add base multiple times!\n");
278 for (
size_t i = 0; i < 6; i++) {
279 _parents.push_back(0);
280 _gearRatios.push_back(0);
281 _jointTypes.push_back(JointType::Nothing);
283 _Xtree.push_back(eye6);
284 _Ibody.push_back(zeroInertia);
285 _Xrot.push_back(eye6);
286 _Irot.push_back(zeroInertia);
287 _bodyNames.push_back(
"N/A");
290 _jointTypes[5] = JointType::FloatingBase;
293 _bodyNames[5] =
"Floating Base";
304 template <
typename T>
318 template <
typename T>
322 if ((
size_t)bodyID >= _nDof) {
323 throw std::runtime_error(
324 "addGroundContactPoint got invalid bodyID: " + std::to_string(bodyID) +
325 " nDofs: " + std::to_string(_nDof) +
"\n");
329 _gcParent.push_back(bodyID);
330 _gcLocation.push_back(location);
334 _pGC.push_back(zero3);
335 _vGC.push_back(zero3);
341 _Jcdqd.push_back(zero3);
343 _compute_contact_info.push_back(
true);
347 _footIndicesGC.push_back(_nGroundContact);
348 _compute_contact_info[_nGroundContact] =
true;
351 resizeSystemMatricies();
352 return _nGroundContact++;
359 template <
typename T>
367 addGroundContactPoint(bodyId,
Vec3<T>(dims(0), dims(1), 0.) / 2);
368 addGroundContactPoint(bodyId,
Vec3<T>(-dims(0), dims(1), 0.) / 2);
369 addGroundContactPoint(bodyId,
Vec3<T>(dims(0), -dims(1), 0.) / 2);
370 addGroundContactPoint(bodyId,
Vec3<T>(-dims(0), -dims(1), 0.) / 2);
372 addGroundContactPoint(bodyId,
Vec3<T>(dims(0), dims(1), -dims(2)) / 2);
373 addGroundContactPoint(bodyId,
Vec3<T>(-dims(0), dims(1), -dims(2)) / 2);
374 addGroundContactPoint(bodyId,
Vec3<T>(dims(0), -dims(1), -dims(2)) / 2);
375 addGroundContactPoint(bodyId,
Vec3<T>(-dims(0), -dims(1), -dims(2)) / 2);
391 template <
typename T>
394 T gearRatio,
int parent,
JointType jointType,
397 if ((
size_t)parent >= _nDof) {
398 throw std::runtime_error(
399 "addBody got invalid parent: " + std::to_string(parent) +
400 " nDofs: " + std::to_string(_nDof) +
"\n");
403 _parents.push_back(parent);
404 _gearRatios.push_back(gearRatio);
405 _jointTypes.push_back(jointType);
406 _jointAxes.push_back(jointAxis);
407 _Xtree.push_back(Xtree);
408 _Xrot.push_back(Xrot);
409 _Ibody.push_back(inertia);
410 _Irot.push_back(rotorInertia);
431 template <
typename T>
434 T gearRatio,
int parent,
JointType jointType,
438 gearRatio, parent, jointType, jointAxis, Xtree, Xrot);
441 template <
typename T>
443 if (_nDof != _parents.size())
444 throw std::runtime_error(
"Invalid dof and parents length");
451 template <
typename T>
454 for (
size_t i = 0; i < _nDof; i++) {
455 totalMass += _Ibody[i].getMass();
464 template <
typename T>
467 for (
size_t i = 0; i < _nDof; i++) {
468 totalMass += _Irot[i].getMass();
478 template <
typename T>
480 if (_kinematicsUpToDate)
return;
484 _state.bodyPosition);
485 _v[5] = _state.bodyVelocity;
486 for (
size_t i = 6; i < _nDof; i++) {
489 _Xup[i] = XJ * _Xtree[i];
490 _S[i] = jointMotionSubspace<T>(_jointTypes[i], _jointAxes[i]);
491 SVec<T> vJ = _S[i] * _state.qd[i - 6];
493 _v[i] = _Xup[i] * _v[_parents[i]] + vJ;
497 _state.q[i - 6] * _gearRatios[i]);
498 _Srot[i] = _S[i] * _gearRatios[i];
499 SVec<T> vJrot = _Srot[i] * _state.qd[i - 6];
500 _Xuprot[i] = XJrot * _Xrot[i];
501 _vrot[i] = _Xuprot[i] * _v[_parents[i]] + vJrot;
509 for (
size_t i = 5; i < _nDof; i++) {
510 if (_parents[i] == 0) {
513 _Xa[i] = _Xup[i] * _Xa[_parents[i]];
520 for (
size_t j = 0; j < _nGroundContact; j++) {
521 if (!_compute_contact_info[j])
continue;
522 size_t i = _gcParent.at(j);
524 SVec<T> vSpatial = Xai * _v[i];
530 _kinematicsUpToDate =
true;
547 template <
typename T>
552 for (
size_t k = 0; k < _nGroundContact; k++) {
557 if (!_compute_contact_info[k])
continue;
559 size_t i = _gcParent.at(k);
562 Mat3<T> Rai = _Xa[i].template block<3, 3>(0, 0).transpose();
573 D3Mat<T> Xout = Xc.template bottomRows<3>();
577 _Jc[k].col(i) = Xout * _S[i];
578 Xout = Xout * _Xup[i];
581 _Jc[k].template leftCols<6>() = Xout;
589 template <
typename T>
591 if (_biasAccelerationsUpToDate)
return;
594 _avp[5] << 0, 0, 0, 0, 0, 0;
597 for (
size_t i = 6; i < _nDof; i++) {
599 _avp[i] = _Xup[i] * _avp[_parents[i]] + _c[i];
600 _avprot[i] = _Xuprot[i] * _avp[_parents[i]] + _crot[i];
602 _biasAccelerationsUpToDate =
true;
609 template <
typename T>
614 aGravity << 0, 0, 0, _gravity[0], _gravity[1], _gravity[2];
615 _ag[5] = _Xup[5] * aGravity;
619 _G.template topRows<6>() = -_IC[5].getMatrix() * _ag[5];
620 for (
size_t i = 6; i < _nDof; i++) {
621 _ag[i] = _Xup[i] * _ag[_parents[i]];
622 _agrot[i] = _Xuprot[i] * _ag[_parents[i]];
625 _G[i] = -_S[i].dot(_IC[i].getMatrix() * _ag[i]) -
626 _Srot[i].dot(_Irot[i].getMatrix() * _agrot[i]);
635 template <
typename T>
640 Mat6<T> Ifb = _Ibody[5].getMatrix();
644 for (
size_t i = 6; i < _nDof; i++) {
646 Mat6<T> Ii = _Ibody[i].getMatrix();
651 Mat6<T> Ir = _Irot[i].getMatrix();
656 for (
size_t i = _nDof - 1; i > 5; i--) {
658 _Cqd[i] = _S[i].dot(_fvp[i]) + _Srot[i].dot(_fvprot[i]);
661 _fvp[_parents[i]] += _Xup[i].transpose() * _fvp[i];
662 _fvp[_parents[i]] += _Xuprot[i].transpose() * _fvprot[i];
666 _Cqd.template topRows<6>() = _fvp[5];
670 template <
typename T>
673 Mat3<T> Rai = _Xa[link_idx].template block<3, 3>(0, 0);
674 Rai.transposeInPlace();
679 template <
typename T>
688 template <
typename T>
697 template <
typename T>
700 forwardAccelerationKinematics();
701 Mat3<T> R = getOrientation(link_idx);
705 template <
typename T>
707 forwardAccelerationKinematics();
708 Mat3<T> R = getOrientation(link_idx);
713 template <
typename T>
717 Mat3<T> Rai = getOrientation(link_idx);
721 template <
typename T>
724 Mat3<T> Rai = getOrientation(link_idx);
730 template <
typename T>
733 Mat3<T> Rai = getOrientation(link_idx);
735 return Rai * _v[link_idx].template head<3>();
739 template <
typename T>
741 forwardAccelerationKinematics();
742 Mat3<T> Rai = getOrientation(link_idx);
743 return Rai * _a[link_idx].template head<3>();
752 template <
typename T>
754 if (_compositeInertiasUpToDate)
return;
758 for (
size_t i = 5; i < _nDof; i++) {
759 _IC[i].setMatrix(_Ibody[i].getMatrix());
763 for (
size_t i = _nDof - 1; i > 5; i--) {
765 _IC[_parents[i]].addMatrix(_Xup[i].transpose() * _IC[i].getMatrix() *
767 _IC[_parents[i]].addMatrix(_Xuprot[i].transpose() * _Irot[i].getMatrix() *
770 _compositeInertiasUpToDate =
true;
777 template <
typename T>
783 _H.template topLeftCorner<6, 6>() = _IC[5].getMatrix();
785 for (
size_t j = 6; j < _nDof; j++) {
787 SVec<T> f = _IC[j].getMatrix() * _S[j];
788 SVec<T> frot = _Irot[j].getMatrix() * _Srot[j];
790 _H(j, j) = _S[j].dot(f) + _Srot[j].dot(frot);
793 f = _Xup[j].transpose() * f + _Xuprot[j].transpose() * frot;
794 size_t i = _parents[j];
797 _H(i, j) = _S[i].dot(f);
801 f = _Xup[i].transpose() *
f;
806 _H.template block<6, 1>(0, j) = f;
807 _H.template block<1, 6>(j, 0) = f.adjoint();
812 template <
typename T>
814 if (_accelerationsUpToDate) {
823 aGravity.template tail<3>() = _gravity;
826 _a[5] = -_Xup[5] * aGravity + _dState.dBodyVelocity;
829 for (
size_t i = 6; i < _nDof; i++) {
831 _a[i] = _Xup[i] * _a[_parents[i]] + _S[i] * _dState.qdd[i - 6] + _c[i];
833 _Xuprot[i] * _a[_parents[i]] + _Srot[i] * _dState.qdd[i - 6] + _crot[i];
835 _accelerationsUpToDate =
true;
844 template <
typename T>
848 forwardAccelerationKinematics();
851 SVec<T> hb = _Ibody[5].getMatrix() * _v[5];
855 for (
size_t i = 6; i < _nDof; i++) {
857 SVec<T> hi = _Ibody[i].getMatrix() * _v[i];
858 SVec<T> hr = _Irot[i].getMatrix() * _vrot[i];
867 for (
size_t i = _nDof - 1; i > 5; i--) {
869 genForce[i] = _S[i].dot(_f[i]) + _Srot[i].dot(_frot[i]);
872 _f[_parents[i]] += _Xup[i].transpose() * _f[i];
873 _f[_parents[i]] += _Xuprot[i].transpose() * _frot[i];
875 genForce.template head<6>() = _f[5];
879 template <
typename T>
884 updateArticulatedBodies();
888 aGravity << 0, 0, 0, _gravity[0], _gravity[1], _gravity[2];
891 SVec<T> ivProduct = _Ibody[5].getMatrix() * _v[5];
895 for (
size_t i = 6; i < _nDof; i++) {
896 ivProduct = _Ibody[i].getMatrix() * _v[i];
900 SVec<T> vJrot = _Srot[i] * _state.qd[i - 6];
901 _vrot[i] = _Xuprot[i] * _v[_parents[i]] + vJrot;
903 ivProduct = _Irot[i].getMatrix() * _vrot[i];
908 for (
size_t i = 5; i < _nDof; i++) {
913 _pA[i] = _pA[i] - iX.transpose() * _externalForces.at(i);
917 for (
size_t i = _nDof - 1; i >= 6; i--) {
918 _u[i] = tau[i - 6] - _S[i].transpose() * _pA[i] -
919 _Srot[i].transpose() * _pArot[i] - _U[i].transpose() * _c[i] -
920 _Urot[i].transpose() * _crot[i];
924 _Xup[i].transpose() * (_pA[i] + _IA[i] * _c[i]) +
925 _Xuprot[i].transpose() * (_pArot[i] + _Irot[i].getMatrix() * _crot[i]) +
926 _Utot[i] * _u[i] / _d[i];
927 _pA[_parents[i]] += pa;
933 _a[5] = _Xup[5] * a0;
934 SVec<T> afb = _invIA5.solve(ub - _IA[5].transpose() * _a[5]);
939 for (
size_t i = 6; i < _nDof; i++) {
941 (_u[i] - _Utot[i].transpose() * _a[_parents[i]]) / _d[i];
942 _a[i] = _Xup[i] * _a[_parents[i]] + _S[i] * dstate.
qdd[i - 6] + _c[i];
948 Rup.transpose() * _state.bodyVelocity.template block<3, 1>(3, 0);
961 template <
typename T>
963 const Vec3<T> &force_ics_at_contact,
966 updateArticulatedBodies();
967 updateForcePropagators();
970 size_t i_opsp = _gcParent.at(gc_index);
973 dstate_out.
qdd.setZero();
976 Mat3<T> Rai = _Xa[i].template block<3, 3>(0, 0).transpose();
981 SVec<T> F = Xc.transpose().template rightCols<3>() * force_ics_at_contact;
983 double LambdaInv = 0;
989 LambdaInv += tmp * tmp / _d[i];
990 dstate_out.
qdd += _qdd_from_subqdd.col(i - 6) * tmp / _d[i];
997 F = _ChiUp[i].transpose() * F;
1016 template <
typename T>
1018 const Vec3<T> &force_ics_at_contact) {
1019 forwardKinematics();
1020 updateArticulatedBodies();
1021 updateForcePropagators();
1023 size_t i_opsp = _gcParent.at(gc_index);
1027 Mat3<T> Rai = _Xa[i].template block<3, 3>(0, 0).transpose();
1032 SVec<T> F = Xc.transpose().template rightCols<3>() * force_ics_at_contact;
1034 double LambdaInv = 0;
1040 LambdaInv += tmp * tmp / _d[i];
1047 F = _ChiUp[i].transpose() * F;
1050 LambdaInv += F.dot(_invIA5.solve(F));
1064 template <
typename T>
1066 const int gc_index,
const D6Mat<T> &force_directions) {
1067 forwardKinematics();
1068 updateArticulatedBodies();
1069 updateForcePropagators();
1071 size_t i_opsp = _gcParent.at(gc_index);
1075 Mat3<T> Rai = _Xa[i].template block<3, 3>(0, 0).transpose();
1080 D6Mat<T> D = Xc.transpose() * force_directions;
1082 size_t m = force_directions.cols();
1089 tmp = D.transpose() * _S[i];
1090 LambdaInv += tmp * tmp.transpose() / _d[i];
1097 D = _ChiUp[i].transpose() * D;
1102 LambdaInv += D.transpose() * _invIA5.solve(D);
DVec< T > inverseDynamics(const FBModelStateDerivative< T > &dState)
Mat3< T > getOrientation(const int link_idx)
void updateForcePropagators()
auto spatialToLinearVelocity(const Eigen::MatrixBase< T > &v, const Eigen::MatrixBase< T2 > &x)
void runABA(const DVec< T > &tau, FBModelStateDerivative< T > &dstate)
Vec3< T > getAngularVelocity(const int link_idx)
auto forceCrossProduct(const Eigen::MatrixBase< T > &a, const Eigen::MatrixBase< T > &b)
typename Eigen::Matrix< T, 6, Eigen::Dynamic > D6Mat
typename Eigen::Matrix< T, 6, 6 > Mat6
Mat6< T > jointXform(JointType joint, CoordinateAxis axis, T q)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Vec3< T > dBodyPosition
typename Eigen::Matrix< T, 3, 3 > Mat3
DVec< T > generalizedCoriolisForce()
int addGroundContactPoint(int bodyID, const Vec3< T > &location, bool isFoot=false)
typename Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > DMat
typename Eigen::Matrix< T, 3, 1 > Vec3
Vec3< T > getLinearAcceleration(const int link_idx, const Vec3< T > &point)
auto translationFromSXform(const Eigen::MatrixBase< T > &X)
auto spatialToLinearAcceleration(const Eigen::MatrixBase< T > &a, const Eigen::MatrixBase< T2 > &v)
auto sXFormPoint(const Eigen::MatrixBase< T > &X, const Eigen::MatrixBase< T2 > &p)
typename Eigen::Matrix< T, 3, Eigen::Dynamic > D3Mat
typename Eigen::Matrix< T, 6, 1 > SVec
Vec3< T > getPosition(const int link_idx, const Vec3< T > &local_pos)
auto createSXform(const Eigen::MatrixBase< T > &R, const Eigen::MatrixBase< T2 > &r)
void forwardAccelerationKinematics()
int addBody(const SpatialInertia< T > &inertia, const SpatialInertia< T > &rotorInertia, T gearRatio, int parent, JointType jointType, CoordinateAxis jointAxis, const Mat6< T > &Xtree, const Mat6< T > &Xrot)
auto motionCrossProduct(const Eigen::MatrixBase< T > &a, const Eigen::MatrixBase< T > &b)
void updateArticulatedBodies()
DMat< T > invContactInertia(const int gc_index, const D6Mat< T > &force_directions)
void resizeSystemMatricies()
Vec3< T > getAngularAcceleration(const int link_idx)
T applyTestForce(const int gc_index, const Vec3< T > &force_ics_at_contact, FBModelStateDerivative< T > &dstate_out)
typename Eigen::Matrix< T, Eigen::Dynamic, 1 > DVec
Mat3< typename T::Scalar > quaternionToRotationMatrix(const Eigen::MatrixBase< T > &q)
void addGroundContactBoxPoints(int bodyId, const Vec3< T > &dims)
typename Eigen::Matrix< T, 10, 1 > MassProperties
Vec3< T > getLinearVelocity(const int link_idx, const Vec3< T > &point)
void addDynamicsVars(int count)
DVec< T > generalizedGravityForce()
typename Eigen::Matrix< T, 3, 3 > RotMat
auto rotationFromSXform(const Eigen::MatrixBase< T > &X)
Implementation of Rigid Body Floating Base model data structure.
void addBase(const SpatialInertia< T > &inertia)
MX f(const MX &x, const MX &u)
auto invertSXform(const Eigen::MatrixBase< T > &X)