24 Vec3<T> bodyDims(_bodyLength, _bodyWidth, _bodyHeight);
38 for (
int legID = 0; legID < 4; legID++) {
47 createSXform(I3, withLegSigns<T>(_abadRotorLocation, legID));
52 _abadGearRatio, baseID, JointType::Revolute,
55 model.
addBody(_abadInertia, _abadRotorInertia, _abadGearRatio, baseID,
64 withLegSigns<T>(_hipLocation, legID));
67 withLegSigns<T>(_hipRotorLocation, legID));
71 _hipGearRatio, bodyID - 1, JointType::Revolute,
74 model.
addBody(_hipInertia, _hipRotorInertia, _hipGearRatio, bodyID - 1,
89 _kneeGearRatio, bodyID - 1, JointType::Revolute,
92 model.
addBody(_kneeInertia, _kneeRotorInertia, _kneeGearRatio, bodyID - 1,
112 template <
typename T>
118 Vec3<T> bodyDims(_bodyLength, _bodyWidth, _bodyHeight);
125 const int baseID = 5;
132 for (
int legID = 0; legID < 4; legID++) {
141 createSXform(I3, withLegSigns<T>(_abadRotorLocation, legID));
146 _abadGearRatio, baseID, JointType::Revolute,
149 model.
addBody(_abadInertia, _abadRotorInertia, _abadGearRatio, baseID,
158 withLegSigns<T>(_hipLocation, legID));
161 withLegSigns<T>(_hipRotorLocation, legID));
165 _hipGearRatio, bodyID - 1, JointType::Revolute,
168 model.
addBody(_hipInertia, _hipRotorInertia, _hipGearRatio, bodyID - 1,
183 _kneeGearRatio, bodyID - 1, JointType::Revolute,
186 model.
addBody(_kneeInertia, _kneeRotorInertia, _kneeGearRatio, bodyID - 1,
206 template <
typename T,
typename T2>
208 static_assert(T2::ColsAtCompileTime == 1 && T2::RowsAtCompileTime == 3,
209 "Must have 3x1 matrix");
212 return Vec3<T>(v[0], -v[1], v[2]);
214 return Vec3<T>(v[0], v[1], v[2]);
216 return Vec3<T>(-v[0], -v[1], v[2]);
218 return Vec3<T>(-v[0], v[1], v[2]);
220 throw std::runtime_error(
"Invalid leg id!");
224 template <
typename T>
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);
typename Eigen::Matrix< T, 6, 6 > Mat6
typename Eigen::Matrix< T, 3, 3 > Mat3
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
void setGravity(Vec3< T > &g)
auto createSXform(const Eigen::MatrixBase< T > &R, const Eigen::MatrixBase< T2 > &r)
Vec3< T > withLegSigns(const Eigen::MatrixBase< T2 > &v, int legID)
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)
std::vector< ActuatorModel< T > > buildActuatorModels()
void addGroundContactBoxPoints(int bodyId, const Vec3< T > &dims)
void addBase(const SpatialInertia< T > &inertia)
FloatingBaseModel< T > buildModel()
Utility functions for manipulating spatial quantities.