Cheetah Software  1.0
Cheetah3.h File Reference

Utility function to build a Cheetah 3 Quadruped object. More...

#include "Dynamics/spatial.h"
#include "FloatingBaseModel.h"
#include "Quadruped.h"
#include "cppTypes.h"
+ Include dependency graph for Cheetah3.h:
+ This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

template<typename T >
Quadruped< T > buildCheetah3 ()
 

Detailed Description

Utility function to build a Cheetah 3 Quadruped object.

This file is based on Cheetah3FullRotorModel_mex.m (originally written by Pat) and builds a model of the Cheetah 3 robot. The inertia parameters of legs and rotors were determined through an experimental procedure described in "Linear Matrix Inequalities for Physically-Consistent Inertial Parameter Identification: A Statistical Perspective on the Mass Distribution" by Wensing, Kim, Slotine. (see https://arxiv.org/abs/1701.04395)

It turns out that the parameters are not fully observable when the base is fixed, which is described in "Observability in Inertial Parameter Identification" by Wensing, Niemeyer, Slotine (see https://arxiv.org/abs/1711.03896).

However, these estimates are still very good and were confirmed against a CAD model of the robot.

Definition in file Cheetah3.h.

Function Documentation

template<typename T >
Quadruped<T> buildCheetah3 ( )

Generate a Quadruped model of Cheetah 3

Definition at line 34 of file Cheetah3.h.

References Quadruped< T >::_abadGearRatio, Quadruped< T >::_abadInertia, Quadruped< T >::_abadLinkLength, Quadruped< T >::_abadLocation, Quadruped< T >::_abadRotorInertia, Quadruped< T >::_abadRotorLocation, Quadruped< T >::_batteryV, Quadruped< T >::_bodyHeight, Quadruped< T >::_bodyInertia, Quadruped< T >::_bodyLength, Quadruped< T >::_bodyMass, Quadruped< T >::_bodyWidth, Quadruped< T >::_hipGearRatio, Quadruped< T >::_hipInertia, Quadruped< T >::_hipLinkLength, Quadruped< T >::_hipLocation, Quadruped< T >::_hipRotorInertia, Quadruped< T >::_hipRotorLocation, Quadruped< T >::_jointDamping, Quadruped< T >::_jointDryFriction, Quadruped< T >::_kneeGearRatio, Quadruped< T >::_kneeInertia, Quadruped< T >::_kneeLinkLength, Quadruped< T >::_kneeLocation, Quadruped< T >::_kneeRotorInertia, Quadruped< T >::_kneeRotorLocation, Quadruped< T >::_maxLegLength, Quadruped< T >::_motorKT, Quadruped< T >::_motorR, Quadruped< T >::_motorTauMax, Quadruped< T >::_robotType, CHEETAH_3, and spatial::rotInertiaOfBox().

34  {
37 
38  cheetah._bodyMass = 26.60;
39  cheetah._bodyLength = .6;
40  cheetah._bodyWidth = .256;
41  cheetah._bodyHeight = .2;
42  cheetah._abadGearRatio = 7.66666666667;
43  cheetah._hipGearRatio = 7.66666666667;
44  cheetah._kneeGearRatio = 8.846;
45  cheetah._abadLinkLength = 0.045;
46  cheetah._hipLinkLength = 0.342;
47  cheetah._kneeLinkLength = 0.345;
48  cheetah._maxLegLength = 0.687;
49 
50  cheetah._batteryV = 65;
51  cheetah._motorKT = 0.266;
52  cheetah._motorR = 0.45;
53  cheetah._jointDamping = .1;
54  cheetah._jointDryFriction = 1;
55  cheetah._motorTauMax = 27.2;
56 
57  MassProperties<T> abadMassProperties, hipMassProperties, kneeMassProperties,
58  abadRotorMassProperties, hipRotorMassProperties, kneeRotorMassProperties;
59 
60  abadMassProperties << 1.645278752937798e+00, 3.987427689943171e-24,
61  1.050694793045323e-01, -7.248117018543008e-03, 6.871761154771191e-03,
62  2.715028710162546e-04, 6.820782113449669e-03, 4.545198314447007e-04,
63  1.000360164583147e-25, -2.201422454848303e-25;
64 
65  hipMassProperties << 1.071200401412615e+00, -7.564034441661159e-04,
66  -3.180527291037499e-02, -1.047496808654130e-01, 2.020976253260794e-02,
67  1.856851411013688e-02, 3.115448656660994e-03, 1.294666102054298e-04,
68  1.217274116646696e-03, -4.116533457993085e-04;
69 
70  kneeMassProperties << 9.019384095786234e-01, 2.215928611851693e-02,
71  3.623331361414656e-03, -4.411934868569409e-02, 2.269554734974269e-02,
72  2.714252268535285e-02, 5.566745484613744e-03, -3.238036214456428e-04,
73  -2.194717054345885e-03, 1.274627163554897e-03;
74 
75  abadRotorMassProperties << 4.999939189070923e-01, 1.184093324655296e-24,
76  1.976769699734076e-03, -3.681440077402916e-04, 9.908339941420835e-04,
77  4.955917167197880e-04, 4.956200895280653e-04, 3.533262919985919e-08,
78  5.751153538955154e-27, 1.342701882012297e-27;
79 
80  hipRotorMassProperties << 5.405045213157799e-01, -3.164547557293410e-03,
81  -6.776800604201722e-03, 7.158586831736347e-04, 4.352341568156850e-04,
82  1.015373256571613e-03, 9.126776037286181e-04, -3.097121515937353e-05,
83  -2.154046949222089e-04, 1.306997274233568e-04;
84 
85  kneeRotorMassProperties << 5.398676189202086e-01, -2.571556872957194e-04,
86  -7.550002224983261e-03, 1.125959428120149e-03, 7.035267590972641e-04,
87  8.693209041255046e-04, 4.122075637011218e-04, -3.986925582339967e-05,
88  -2.295396403157565e-04, 2.324567952553503e-05;
89 
90  cheetah._abadInertia = SpatialInertia<T>(abadMassProperties);
91  cheetah._hipInertia = SpatialInertia<T>(hipMassProperties);
92  cheetah._kneeInertia = SpatialInertia<T>(kneeMassProperties);
93  cheetah._abadRotorInertia = SpatialInertia<T>(abadRotorMassProperties);
94  cheetah._hipRotorInertia = SpatialInertia<T>(hipRotorMassProperties);
95  cheetah._kneeRotorInertia = SpatialInertia<T>(kneeRotorMassProperties);
96  Vec3<T> bodyCOM(0, 0, 0);
97  Vec3<T> bodyDims(cheetah._bodyLength, cheetah._bodyWidth,
98  cheetah._bodyHeight);
100  cheetah._bodyMass, bodyCOM, rotInertiaOfBox(cheetah._bodyMass, bodyDims));
101 
102  // this doesn't generalize to the mini cheetah?
103  cheetah._abadLocation =
104  Vec3<T>(cheetah._bodyLength, cheetah._bodyWidth, 0) * 0.5;
105 
106  // note that this is wrong to match a small bug in the actual simulator, just
107  // to test that I get the right answer. TODO fix!
108  cheetah._abadRotorLocation = Vec3<T>(0, -cheetah._bodyWidth / 2., 0);
109 
110  cheetah._hipLocation = Vec3<T>(0, cheetah._abadLinkLength, 0);
111  cheetah._hipRotorLocation = Vec3<T>(0, cheetah._abadLinkLength, 0);
112  cheetah._kneeLocation = Vec3<T>(0, 0, -cheetah._hipLinkLength);
113  cheetah._kneeRotorLocation = Vec3<T>(0, 0, 0);
114  return cheetah;
115 }
T _bodyMass
Definition: Quadruped.h:60
T _batteryV
Definition: Quadruped.h:63
T _hipLinkLength
Definition: Quadruped.h:62
T _abadGearRatio
Definition: Quadruped.h:61
SpatialInertia< T > _abadRotorInertia
Definition: Quadruped.h:66
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
T _bodyLength
Definition: Quadruped.h:60
T _kneeLinkLength
Definition: Quadruped.h:62
T _motorKT
Definition: Quadruped.h:63
Vec3< T > _hipRotorLocation
Definition: Quadruped.h:68
Vec3< T > _abadRotorLocation
Definition: Quadruped.h:68
SpatialInertia< T > _kneeInertia
Definition: Quadruped.h:66
T _jointDamping
Definition: Quadruped.h:65
Vec3< T > _hipLocation
Definition: Quadruped.h:68
T _hipGearRatio
Definition: Quadruped.h:61
T _kneeGearRatio
Definition: Quadruped.h:61
SpatialInertia< T > _hipRotorInertia
Definition: Quadruped.h:66
T _bodyWidth
Definition: Quadruped.h:60
T _abadLinkLength
Definition: Quadruped.h:62
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RobotType _robotType
Definition: Quadruped.h:59
SpatialInertia< T > _abadInertia
Definition: Quadruped.h:66
Vec3< T > _kneeRotorLocation
Definition: Quadruped.h:68
T _bodyHeight
Definition: Quadruped.h:60
SpatialInertia< T > _bodyInertia
Definition: Quadruped.h:66
SpatialInertia< T > _hipInertia
Definition: Quadruped.h:66
T _maxLegLength
Definition: Quadruped.h:62
T _jointDryFriction
Definition: Quadruped.h:65
typename Eigen::Matrix< T, 10, 1 > MassProperties
Definition: cppTypes.h:98
Mat3< typename T::Scalar > rotInertiaOfBox(typename T::Scalar mass, const Eigen::MatrixBase< T > &dims)
Definition: spatial.h:245
SpatialInertia< T > _kneeRotorInertia
Definition: Quadruped.h:66
Vec3< T > _abadLocation
Definition: Quadruped.h:68
T _motorTauMax
Definition: Quadruped.h:64
Vec3< T > _kneeLocation
Definition: Quadruped.h:68

+ Here is the call graph for this function: