Cheetah Software  1.0
MiniCheetah.h File Reference

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

#include "FloatingBaseModel.h"
#include "Quadruped.h"
+ Include dependency graph for MiniCheetah.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 > buildMiniCheetah ()
 

Detailed Description

Utility function to build a Mini Cheetah Quadruped object.

This file is based on MiniCheetahFullRotorModel_mex.m and builds a model of the Mini Cheetah robot. The inertia parameters of all bodies are determined from CAD.

Definition in file MiniCheetah.h.

Function Documentation

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

Generate a Quadruped model of Mini Cheetah

Definition at line 20 of file MiniCheetah.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, and MINI_CHEETAH.

20  {
23 
24  cheetah._bodyMass = 3.3;
25  cheetah._bodyLength = 0.19 * 2;
26  cheetah._bodyWidth = 0.049 * 2;
27  cheetah._bodyHeight = 0.05 * 2;
28  cheetah._abadGearRatio = 6;
29  cheetah._hipGearRatio = 6;
30  cheetah._kneeGearRatio = 9.33;
31  cheetah._abadLinkLength = 0.062;
32  cheetah._hipLinkLength = 0.209;
33  cheetah._kneeLinkLength = 0.175;
34  cheetah._maxLegLength = 0.384;
35 
36  cheetah._motorTauMax = 3.f;
37  cheetah._batteryV = 24;
38  cheetah._motorKT = .05; // this is flux linkage * pole pairs
39  cheetah._motorR = 0.173;
40  cheetah._jointDamping = .01;
41  cheetah._jointDryFriction = .2;
42 
43  // rotor inertia if the rotor is oriented so it spins around the z-axis
44  Mat3<T> rotorRotationalInertiaZ;
45  rotorRotationalInertiaZ << 33, 0, 0, 0, 33, 0, 0, 0, 63;
46  rotorRotationalInertiaZ = 1e-6 * rotorRotationalInertiaZ;
47 
48  Mat3<T> RY = coordinateRotation<T>(CoordinateAxis::Y, M_PI / 2);
49  Mat3<T> RX = coordinateRotation<T>(CoordinateAxis::X, M_PI / 2);
50  Mat3<T> rotorRotationalInertiaX =
51  RY * rotorRotationalInertiaZ * RY.transpose();
52  Mat3<T> rotorRotationalInertiaY =
53  RX * rotorRotationalInertiaZ * RX.transpose();
54 
55  // spatial inertias
56  Mat3<T> abadRotationalInertia;
57  abadRotationalInertia << 381, 58, 0.45, 58, 560, 0.95, 0.45, 0.95, 444;
58  abadRotationalInertia = abadRotationalInertia * 1e-6;
59  Vec3<T> abadCOM(0, 0.036, 0); // LEFT
60  SpatialInertia<T> abadInertia(0.54, abadCOM, abadRotationalInertia);
61 
62  Mat3<T> hipRotationalInertia;
63  hipRotationalInertia << 1983, 245, 13, 245, 2103, 1.5, 13, 1.5, 408;
64  hipRotationalInertia = hipRotationalInertia * 1e-6;
65  Vec3<T> hipCOM(0, 0.016, -0.02);
66  SpatialInertia<T> hipInertia(0.634, hipCOM, hipRotationalInertia);
67 
68  Mat3<T> kneeRotationalInertia, kneeRotationalInertiaRotated;
69  kneeRotationalInertiaRotated << 6, 0, 0, 0, 248, 0, 0, 0, 245;
70  kneeRotationalInertiaRotated = kneeRotationalInertiaRotated * 1e-6;
71  kneeRotationalInertia = RY * kneeRotationalInertiaRotated * RY.transpose();
72  Vec3<T> kneeCOM(0, 0, -0.061);
73  SpatialInertia<T> kneeInertia(0.064, kneeCOM, kneeRotationalInertia);
74 
75  Vec3<T> rotorCOM(0, 0, 0);
76  SpatialInertia<T> rotorInertiaX(0.055, rotorCOM, rotorRotationalInertiaX);
77  SpatialInertia<T> rotorInertiaY(0.055, rotorCOM, rotorRotationalInertiaY);
78 
79  Mat3<T> bodyRotationalInertia;
80  bodyRotationalInertia << 11253, 0, 0, 0, 36203, 0, 0, 0, 42673;
81  bodyRotationalInertia = bodyRotationalInertia * 1e-6;
82  Vec3<T> bodyCOM(0, 0, 0);
83  SpatialInertia<T> bodyInertia(cheetah._bodyMass, bodyCOM,
84  bodyRotationalInertia);
85 
86  cheetah._abadInertia = abadInertia;
87  cheetah._hipInertia = hipInertia;
88  cheetah._kneeInertia = kneeInertia;
89  cheetah._abadRotorInertia = rotorInertiaX;
90  cheetah._hipRotorInertia = rotorInertiaY;
91  cheetah._kneeRotorInertia = rotorInertiaY;
92  cheetah._bodyInertia = bodyInertia;
93 
94  // locations
95  cheetah._abadRotorLocation = Vec3<T>(0.125, 0.049, 0);
96  cheetah._abadLocation =
97  Vec3<T>(cheetah._bodyLength, cheetah._bodyWidth, 0) * 0.5;
98  cheetah._hipLocation = Vec3<T>(0, cheetah._abadLinkLength, 0);
99  cheetah._hipRotorLocation = Vec3<T>(0, 0.04, 0);
100  cheetah._kneeLocation = Vec3<T>(0, 0, -cheetah._hipLinkLength);
101  cheetah._kneeRotorLocation = Vec3<T>(0, 0, 0);
102 
103  return cheetah;
104 }
T _bodyMass
Definition: Quadruped.h:60
T _batteryV
Definition: Quadruped.h:63
T _hipLinkLength
Definition: Quadruped.h:62
T _abadGearRatio
Definition: Quadruped.h:61
typename Eigen::Matrix< T, 3, 3 > Mat3
Definition: cppTypes.h:54
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
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