Cheetah Software  1.0
Quadruped< T > Class Template Reference

#include <Quadruped.h>

+ Inheritance diagram for Quadruped< T >:
+ Collaboration diagram for Quadruped< T >:

Public Member Functions

FloatingBaseModel< T > buildModel ()
 
bool buildModel (FloatingBaseModel< T > &model)
 
std::vector< ActuatorModel< T > > buildActuatorModels ()
 
Vec3< T > getHipLocation (int leg)
 

Static Public Member Functions

static T getSideSign (int leg)
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW RobotType _robotType
 
_bodyLength
 
_bodyWidth
 
_bodyHeight
 
_bodyMass
 
_abadGearRatio
 
_hipGearRatio
 
_kneeGearRatio
 
_abadLinkLength
 
_hipLinkLength
 
_kneeLinkLength
 
_maxLegLength
 
_motorKT
 
_motorR
 
_batteryV
 
_motorTauMax
 
_jointDamping
 
_jointDryFriction
 
SpatialInertia< T > _abadInertia
 
SpatialInertia< T > _hipInertia
 
SpatialInertia< T > _kneeInertia
 
SpatialInertia< T > _abadRotorInertia
 
SpatialInertia< T > _hipRotorInertia
 
SpatialInertia< T > _kneeRotorInertia
 
SpatialInertia< T > _bodyInertia
 
Vec3< T > _abadLocation
 
Vec3< T > _abadRotorLocation
 
Vec3< T > _hipLocation
 
Vec3< T > _hipRotorLocation
 
Vec3< T > _kneeLocation
 
Vec3< T > _kneeRotorLocation
 

Detailed Description

template<typename T>
class Quadruped< T >

Representation of a quadruped robot's physical properties.

When viewed from the top, the quadruped's legs are:

FRONT 2 1 RIGHT 4 3 BACK

Definition at line 56 of file Quadruped.h.

Member Function Documentation

template<typename T >
std::vector< ActuatorModel< T > > Quadruped< T >::buildActuatorModels ( )

Definition at line 225 of file Quadruped.cpp.

225  {
226  std::vector<ActuatorModel<T>> models;
227  models.emplace_back(_abadGearRatio, _motorKT, _motorR, _batteryV,
229  models.emplace_back(_hipGearRatio, _motorKT, _motorR, _batteryV,
231  models.emplace_back(_kneeGearRatio, _motorKT, _motorR, _batteryV,
233  return models;
234 }
T _batteryV
Definition: Quadruped.h:63
T _abadGearRatio
Definition: Quadruped.h:61
T _motorKT
Definition: Quadruped.h:63
T _jointDamping
Definition: Quadruped.h:65
T _hipGearRatio
Definition: Quadruped.h:61
T _kneeGearRatio
Definition: Quadruped.h:61
T _jointDryFriction
Definition: Quadruped.h:65
T _motorTauMax
Definition: Quadruped.h:64

+ Here is the caller graph for this function:

template<typename T >
FloatingBaseModel< T > Quadruped< T >::buildModel ( )

Build a FloatingBaseModel of the quadruped

Definition at line 113 of file Quadruped.cpp.

References FloatingBaseModel< T >::addBase(), FloatingBaseModel< T >::addBody(), FloatingBaseModel< T >::addGroundContactBoxPoints(), FloatingBaseModel< T >::addGroundContactPoint(), spatial::createSXform(), FloatingBaseModel< T >::setGravity(), ori::X, ori::Y, and ori::Z.

113  {
114  FloatingBaseModel<T> model;
115 
116  // we assume the cheetah's body (not including rotors) can be modeled as a
117  // uniformly distributed box.
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 {
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 {
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 {
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 }
T _hipLinkLength
Definition: Quadruped.h:62
typename Eigen::Matrix< T, 6, 6 > Mat6
Definition: cppTypes.h:70
T _abadGearRatio
Definition: Quadruped.h:61
typename Eigen::Matrix< T, 3, 3 > Mat3
Definition: cppTypes.h:54
int addGroundContactPoint(int bodyID, const Vec3< T > &location, bool isFoot=false)
SpatialInertia< T > _abadRotorInertia
Definition: Quadruped.h:66
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
void setGravity(Vec3< T > &g)
T _bodyLength
Definition: Quadruped.h:60
T _kneeLinkLength
Definition: Quadruped.h:62
Vec3< T > _hipRotorLocation
Definition: Quadruped.h:68
Vec3< T > _abadRotorLocation
Definition: Quadruped.h:68
SpatialInertia< T > _kneeInertia
Definition: Quadruped.h:66
Vec3< T > _hipLocation
Definition: Quadruped.h:68
T _hipGearRatio
Definition: Quadruped.h:61
auto createSXform(const Eigen::MatrixBase< T > &R, const Eigen::MatrixBase< T2 > &r)
Definition: spatial.h:140
T _kneeGearRatio
Definition: Quadruped.h:61
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)
SpatialInertia< T > _hipRotorInertia
Definition: Quadruped.h:66
T _bodyWidth
Definition: Quadruped.h:60
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
void addGroundContactBoxPoints(int bodyId, const Vec3< T > &dims)
SpatialInertia< T > _kneeRotorInertia
Definition: Quadruped.h:66
void addBase(const SpatialInertia< T > &inertia)
Vec3< T > _abadLocation
Definition: Quadruped.h:68
Vec3< T > _kneeLocation
Definition: Quadruped.h:68

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

template<typename T>
bool Quadruped< T >::buildModel ( FloatingBaseModel< T > &  model)

Build a FloatingBaseModel of the quadruped

Definition at line 21 of file Quadruped.cpp.

References FloatingBaseModel< T >::addBase(), FloatingBaseModel< T >::addBody(), FloatingBaseModel< T >::addGroundContactBoxPoints(), FloatingBaseModel< T >::addGroundContactPoint(), spatial::createSXform(), FloatingBaseModel< T >::setGravity(), ori::X, ori::Y, and ori::Z.

21  {
22  // we assume the cheetah's body (not including rotors) can be modeled as a
23  // uniformly distributed box.
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 {
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 {
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 {
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 }
T _hipLinkLength
Definition: Quadruped.h:62
typename Eigen::Matrix< T, 6, 6 > Mat6
Definition: cppTypes.h:70
T _abadGearRatio
Definition: Quadruped.h:61
typename Eigen::Matrix< T, 3, 3 > Mat3
Definition: cppTypes.h:54
int addGroundContactPoint(int bodyID, const Vec3< T > &location, bool isFoot=false)
SpatialInertia< T > _abadRotorInertia
Definition: Quadruped.h:66
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
void setGravity(Vec3< T > &g)
T _bodyLength
Definition: Quadruped.h:60
T _kneeLinkLength
Definition: Quadruped.h:62
Vec3< T > _hipRotorLocation
Definition: Quadruped.h:68
Vec3< T > _abadRotorLocation
Definition: Quadruped.h:68
SpatialInertia< T > _kneeInertia
Definition: Quadruped.h:66
Vec3< T > _hipLocation
Definition: Quadruped.h:68
T _hipGearRatio
Definition: Quadruped.h:61
auto createSXform(const Eigen::MatrixBase< T > &R, const Eigen::MatrixBase< T2 > &r)
Definition: spatial.h:140
T _kneeGearRatio
Definition: Quadruped.h:61
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)
SpatialInertia< T > _hipRotorInertia
Definition: Quadruped.h:66
T _bodyWidth
Definition: Quadruped.h:60
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
void addGroundContactBoxPoints(int bodyId, const Vec3< T > &dims)
SpatialInertia< T > _kneeRotorInertia
Definition: Quadruped.h:66
void addBase(const SpatialInertia< T > &inertia)
Vec3< T > _abadLocation
Definition: Quadruped.h:68
Vec3< T > _kneeLocation
Definition: Quadruped.h:68

+ Here is the call graph for this function:

template<typename T>
Vec3<T> Quadruped< T >::getHipLocation ( int  leg)
inline

Get location of the hip for the given leg in robot frame

Definition at line 83 of file Quadruped.h.

83  {
84  assert(leg >= 0 && leg < 4);
85  Vec3<T> pHip((leg == 0 || leg == 1) ? _abadLocation(0) : -_abadLocation(0),
86  (leg == 1 || leg == 3) ? _abadLocation(1) : -_abadLocation(1),
87  _abadLocation(2));
88  return pHip;
89  }
typename Eigen::Matrix< T, 3, 1 > Vec3
Definition: cppTypes.h:26
Vec3< T > _abadLocation
Definition: Quadruped.h:68

+ Here is the caller graph for this function:

template<typename T>
static T Quadruped< T >::getSideSign ( int  leg)
inlinestatic

Definition at line 74 of file Quadruped.h.

74  {
75  const T sideSigns[4] = {-1, 1, -1, 1};
76  assert(leg >= 0 && leg < 4);
77  return sideSigns[leg];
78  }

+ Here is the caller graph for this function:

Member Data Documentation

template<typename T>
T Quadruped< T >::_abadGearRatio

Definition at line 61 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_abadInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_abadLinkLength

Definition at line 62 of file Quadruped.h.

template<typename T>
Vec3<T> Quadruped< T >::_abadLocation

Definition at line 68 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_abadRotorInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
Vec3<T> Quadruped< T >::_abadRotorLocation

Definition at line 68 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_batteryV

Definition at line 63 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_bodyHeight

Definition at line 60 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_bodyInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_bodyLength

Definition at line 60 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_bodyMass

Definition at line 60 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_bodyWidth

Definition at line 60 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_hipGearRatio

Definition at line 61 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_hipInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_hipLinkLength

Definition at line 62 of file Quadruped.h.

template<typename T>
Vec3<T> Quadruped< T >::_hipLocation

Definition at line 68 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_hipRotorInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
Vec3<T> Quadruped< T >::_hipRotorLocation

Definition at line 68 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_jointDamping

Definition at line 65 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_jointDryFriction

Definition at line 65 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_kneeGearRatio

Definition at line 61 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_kneeInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_kneeLinkLength

Definition at line 62 of file Quadruped.h.

template<typename T>
Vec3<T> Quadruped< T >::_kneeLocation

Definition at line 68 of file Quadruped.h.

template<typename T>
SpatialInertia<T> Quadruped< T >::_kneeRotorInertia

Definition at line 66 of file Quadruped.h.

template<typename T>
Vec3<T> Quadruped< T >::_kneeRotorLocation

Definition at line 68 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_maxLegLength

Definition at line 62 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_motorKT

Definition at line 63 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_motorR

Definition at line 63 of file Quadruped.h.

template<typename T>
T Quadruped< T >::_motorTauMax

Definition at line 64 of file Quadruped.h.

template<typename T>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RobotType Quadruped< T >::_robotType

Definition at line 59 of file Quadruped.h.


The documentation for this class was generated from the following files: