Cheetah Software  1.0
Quadruped.cpp
Go to the documentation of this file.
1 
10 #include "Dynamics/Quadruped.h"
11 #include "Dynamics/spatial.h"
12 #include "Math/orientation_tools.h"
13 
14 using namespace ori;
15 using namespace spatial;
16 
20 template <typename T>
22  // we assume the cheetah's body (not including rotors) can be modeled as a
23  // uniformly distributed box.
24  Vec3<T> bodyDims(_bodyLength, _bodyWidth, _bodyHeight);
25  // model.addBase(_bodyMass, Vec3<T>(0,0,0), rotInertiaOfBox(_bodyMass,
26  // bodyDims));
27  model.addBase(_bodyInertia);
28  // add contact for the cheetah's body
29  model.addGroundContactBoxPoints(5, bodyDims);
30 
31  const int baseID = 5;
32  int bodyID = baseID;
33  T sideSign = -1;
34 
36 
37  // loop over 4 legs
38  for (int legID = 0; legID < 4; legID++) {
39  // Ab/Ad joint
40  // int addBody(const SpatialInertia<T>& inertia, const SpatialInertia<T>&
41  // rotorInertia, T gearRatio,
42  // int parent, JointType jointType, CoordinateAxis jointAxis,
43  // const Mat6<T>& Xtree, const Mat6<T>& Xrot);
44  bodyID++;
45  Mat6<T> xtreeAbad = createSXform(I3, withLegSigns<T>(_abadLocation, legID));
46  Mat6<T> xtreeAbadRotor =
47  createSXform(I3, withLegSigns<T>(_abadRotorLocation, legID));
48 
49  if (sideSign < 0) {
50  model.addBody(_abadInertia.flipAlongAxis(CoordinateAxis::Y),
51  _abadRotorInertia.flipAlongAxis(CoordinateAxis::Y),
52  _abadGearRatio, baseID, JointType::Revolute,
53  CoordinateAxis::X, xtreeAbad, xtreeAbadRotor);
54  } else {
55  model.addBody(_abadInertia, _abadRotorInertia, _abadGearRatio, baseID,
56  JointType::Revolute, CoordinateAxis::X, xtreeAbad,
57  xtreeAbadRotor);
58  }
59 
60  // Hip Joint
61  bodyID++;
62  Mat6<T> xtreeHip =
63  createSXform(coordinateRotation<T>(CoordinateAxis::Z, T(M_PI)),
64  withLegSigns<T>(_hipLocation, legID));
65  Mat6<T> xtreeHipRotor =
66  createSXform(coordinateRotation<T>(CoordinateAxis::Z, T(M_PI)),
67  withLegSigns<T>(_hipRotorLocation, legID));
68  if (sideSign < 0) {
69  model.addBody(_hipInertia.flipAlongAxis(CoordinateAxis::Y),
70  _hipRotorInertia.flipAlongAxis(CoordinateAxis::Y),
71  _hipGearRatio, bodyID - 1, JointType::Revolute,
72  CoordinateAxis::Y, xtreeHip, xtreeHipRotor);
73  } else {
74  model.addBody(_hipInertia, _hipRotorInertia, _hipGearRatio, bodyID - 1,
75  JointType::Revolute, CoordinateAxis::Y, xtreeHip,
76  xtreeHipRotor);
77  }
78 
79  // add knee ground contact point
80  model.addGroundContactPoint(bodyID, Vec3<T>(0, 0, -_hipLinkLength));
81 
82  // Knee Joint
83  bodyID++;
84  Mat6<T> xtreeKnee = createSXform(I3, _kneeLocation);
85  Mat6<T> xtreeKneeRotor = createSXform(I3, _kneeRotorLocation);
86  if (sideSign < 0) {
87  model.addBody(_kneeInertia.flipAlongAxis(CoordinateAxis::Y),
88  _kneeRotorInertia.flipAlongAxis(CoordinateAxis::Y),
89  _kneeGearRatio, bodyID - 1, JointType::Revolute,
90  CoordinateAxis::Y, xtreeKnee, xtreeKneeRotor);
91  } else {
92  model.addBody(_kneeInertia, _kneeRotorInertia, _kneeGearRatio, bodyID - 1,
93  JointType::Revolute, CoordinateAxis::Y, xtreeKnee,
94  xtreeKneeRotor);
95  }
96 
97  // add foot
98  model.addGroundContactPoint(bodyID, Vec3<T>(0, 0, -_kneeLinkLength), true);
99 
100  sideSign *= -1;
101  }
102 
103  Vec3<T> g(0, 0, -9.81);
104  model.setGravity(g);
105 
106  return true;
107 }
108 
112 template <typename T>
114  FloatingBaseModel<T> model;
115 
116  // we assume the cheetah's body (not including rotors) can be modeled as a
117  // uniformly distributed box.
118  Vec3<T> bodyDims(_bodyLength, _bodyWidth, _bodyHeight);
119  // model.addBase(_bodyMass, Vec3<T>(0,0,0), rotInertiaOfBox(_bodyMass,
120  // bodyDims));
121  model.addBase(_bodyInertia);
122  // add contact for the cheetah's body
123  model.addGroundContactBoxPoints(5, bodyDims);
124 
125  const int baseID = 5;
126  int bodyID = baseID;
127  T sideSign = -1;
128 
129  Mat3<T> I3 = Mat3<T>::Identity();
130 
131  // loop over 4 legs
132  for (int legID = 0; legID < 4; legID++) {
133  // Ab/Ad joint
134  // int addBody(const SpatialInertia<T>& inertia, const SpatialInertia<T>&
135  // rotorInertia, T gearRatio,
136  // int parent, JointType jointType, CoordinateAxis jointAxis,
137  // const Mat6<T>& Xtree, const Mat6<T>& Xrot);
138  bodyID++;
139  Mat6<T> xtreeAbad = createSXform(I3, withLegSigns<T>(_abadLocation, legID));
140  Mat6<T> xtreeAbadRotor =
141  createSXform(I3, withLegSigns<T>(_abadRotorLocation, legID));
142 
143  if (sideSign < 0) {
144  model.addBody(_abadInertia.flipAlongAxis(CoordinateAxis::Y),
145  _abadRotorInertia.flipAlongAxis(CoordinateAxis::Y),
146  _abadGearRatio, baseID, JointType::Revolute,
147  CoordinateAxis::X, xtreeAbad, xtreeAbadRotor);
148  } else {
149  model.addBody(_abadInertia, _abadRotorInertia, _abadGearRatio, baseID,
150  JointType::Revolute, CoordinateAxis::X, xtreeAbad,
151  xtreeAbadRotor);
152  }
153 
154  // Hip Joint
155  bodyID++;
156  Mat6<T> xtreeHip =
157  createSXform(coordinateRotation<T>(CoordinateAxis::Z, T(M_PI)),
158  withLegSigns<T>(_hipLocation, legID));
159  Mat6<T> xtreeHipRotor =
160  createSXform(coordinateRotation<T>(CoordinateAxis::Z, T(M_PI)),
161  withLegSigns<T>(_hipRotorLocation, legID));
162  if (sideSign < 0) {
163  model.addBody(_hipInertia.flipAlongAxis(CoordinateAxis::Y),
164  _hipRotorInertia.flipAlongAxis(CoordinateAxis::Y),
165  _hipGearRatio, bodyID - 1, JointType::Revolute,
166  CoordinateAxis::Y, xtreeHip, xtreeHipRotor);
167  } else {
168  model.addBody(_hipInertia, _hipRotorInertia, _hipGearRatio, bodyID - 1,
169  JointType::Revolute, CoordinateAxis::Y, xtreeHip,
170  xtreeHipRotor);
171  }
172 
173  // add knee ground contact point
174  model.addGroundContactPoint(bodyID, Vec3<T>(0, 0, -_hipLinkLength));
175 
176  // Knee Joint
177  bodyID++;
178  Mat6<T> xtreeKnee = createSXform(I3, _kneeLocation);
179  Mat6<T> xtreeKneeRotor = createSXform(I3, _kneeRotorLocation);
180  if (sideSign < 0) {
181  model.addBody(_kneeInertia.flipAlongAxis(CoordinateAxis::Y),
182  _kneeRotorInertia.flipAlongAxis(CoordinateAxis::Y),
183  _kneeGearRatio, bodyID - 1, JointType::Revolute,
184  CoordinateAxis::Y, xtreeKnee, xtreeKneeRotor);
185  } else {
186  model.addBody(_kneeInertia, _kneeRotorInertia, _kneeGearRatio, bodyID - 1,
187  JointType::Revolute, CoordinateAxis::Y, xtreeKnee,
188  xtreeKneeRotor);
189  }
190 
191  // add foot
192  model.addGroundContactPoint(bodyID, Vec3<T>(0, 0, -_kneeLinkLength), true);
193 
194  sideSign *= -1;
195  }
196 
197  Vec3<T> g(0, 0, -9.81);
198  model.setGravity(g);
199 
200  return model;
201 }
202 
206 template <typename T, typename T2>
207 Vec3<T> withLegSigns(const Eigen::MatrixBase<T2>& v, int legID) {
208  static_assert(T2::ColsAtCompileTime == 1 && T2::RowsAtCompileTime == 3,
209  "Must have 3x1 matrix");
210  switch (legID) {
211  case 0:
212  return Vec3<T>(v[0], -v[1], v[2]);
213  case 1:
214  return Vec3<T>(v[0], v[1], v[2]);
215  case 2:
216  return Vec3<T>(-v[0], -v[1], v[2]);
217  case 3:
218  return Vec3<T>(-v[0], v[1], v[2]);
219  default:
220  throw std::runtime_error("Invalid leg id!");
221  }
222 }
223 
224 template <typename T>
225 std::vector<ActuatorModel<T>> Quadruped<T>::buildActuatorModels() {
226  std::vector<ActuatorModel<T>> models;
227  models.emplace_back(_abadGearRatio, _motorKT, _motorR, _batteryV,
228  _jointDamping, _jointDryFriction, _motorTauMax);
229  models.emplace_back(_hipGearRatio, _motorKT, _motorR, _batteryV,
230  _jointDamping, _jointDryFriction, _motorTauMax);
231  models.emplace_back(_kneeGearRatio, _motorKT, _motorR, _batteryV,
232  _jointDamping, _jointDryFriction, _motorTauMax);
233  return models;
234 }
235 
236 template class Quadruped<double>;
237 template class Quadruped<float>;
typename Eigen::Matrix< T, 6, 6 > Mat6
Definition: cppTypes.h:70
typename Eigen::Matrix< T, 3, 3 > Mat3
Definition: cppTypes.h:54
int addGroundContactPoint(int bodyID, const Vec3< T > &location, bool isFoot=false)
Data structure containing parameters for quadruped robot.
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
void setGravity(Vec3< T > &g)
auto createSXform(const Eigen::MatrixBase< T > &R, const Eigen::MatrixBase< T2 > &r)
Definition: spatial.h:140
Vec3< T > withLegSigns(const Eigen::MatrixBase< T2 > &v, int legID)
Definition: Quadruped.cpp:207
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)
Utility functions for 3D rotations.
std::vector< ActuatorModel< T > > buildActuatorModels()
Definition: Quadruped.cpp:225
void addGroundContactBoxPoints(int bodyId, const Vec3< T > &dims)
void addBase(const SpatialInertia< T > &inertia)
FloatingBaseModel< T > buildModel()
Definition: Quadruped.cpp:113
Utility functions for manipulating spatial quantities.