forked from amburkoff/be2r_cmpc_unitree
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathQuadruped.h
109 lines (97 loc) · 3.17 KB
/
Quadruped.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
/*! @file Quadruped.h
* @brief Data structure containing parameters for quadruped robot
*
* This file contains the Quadruped class. This stores all the parameters for
* a quadruped robot. There are utility functions to generate Quadruped objects
* for Cheetah 3 (and eventually mini-cheetah). There is a buildModel() method
* which can be used to create a floating-base dynamics model of the quadruped.
*/
#ifndef LIBBIOMIMETICS_QUADRUPED_H
#define LIBBIOMIMETICS_QUADRUPED_H
#include "Dynamics/ActuatorModel.h"
#include "Dynamics/FloatingBaseModel.h"
#include "Dynamics/SpatialInertia.h"
#include <vector>
#include <eigen3/Eigen/StdVector>
/*!
* Basic parameters for a cheetah-shaped robot
*/
namespace cheetah
{
constexpr size_t num_act_joint = 12;
constexpr size_t num_q = 19;
constexpr size_t dim_config = 18;
constexpr size_t num_leg = 4;
constexpr size_t num_leg_joint = 3;
} // namespace cheetah
/*!
* Link indices for cheetah-shaped robots
*/
namespace linkID
{
constexpr size_t FR = 9; // Front Right Foot
constexpr size_t FL = 11; // Front Left Foot
constexpr size_t HR = 13; // Hind Right Foot
constexpr size_t HL = 15; // Hind Left Foot
constexpr size_t FR_abd = 2; // Front Right Abduction
constexpr size_t FL_abd = 0; // Front Left Abduction
constexpr size_t HR_abd = 3; // Hind Right Abduction
constexpr size_t HL_abd = 1; // Hind Left Abduction
} // namespace linkID
using std::vector;
/*!
* 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
*
*/
template <typename T>
class Quadruped
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
RobotType _robotType;
T _whole_mass;
T _bodyLength, _bodyWidth, _bodyHeight, _bodyMass;
T _abadGearRatio, _hipGearRatio, _kneeGearRatio;
T _abadLinkLength, _hipLinkLength, _kneeLinkLength, _kneeLinkY_offset, _maxLegLength;
T _motorKT, _motorR, _batteryV;
T _motorTauMax;
T _jointDamping, _jointDryFriction;
SpatialInertia<T> _abadInertia, _hipInertia, _kneeInertia, _abadRotorInertia, _hipRotorInertia, _kneeRotorInertia, _bodyInertia;
Vec3<T> _abadLocation, _abadRotorLocation, _hipLocation, _hipRotorLocation, _kneeLocation, _kneeRotorLocation;
FloatingBaseModel<T> buildModel();
bool buildModel(FloatingBaseModel<T>& model);
std::vector<ActuatorModel<T>> buildActuatorModels();
/*!
* Get if the i-th leg is on the left (+) or right (-) of the robot.
* @param leg : the leg index
* @return The side sign (-1 for right legs, +1 for left legs)
*/
static T getSideSign(int leg)
{
const T sideSigns[4] = {-1, 1, -1, 1};
assert(leg >= 0 && leg < 4);
return sideSigns[leg];
}
/*!
* Get location of the hip for the given leg in robot frame
* @param leg : the leg index
*/
Vec3<T> getHipLocation(int leg)
{
assert(leg >= 0 && leg < 4);
Vec3<T> pHip((leg == 0 || leg == 1) ? _abadLocation(0) : -_abadLocation(0),
(leg == 1 || leg == 3) ? _abadLocation(1) : -_abadLocation(1),
_abadLocation(2));
return pHip;
}
};
template <typename T, typename T2>
Vec3<T> withLegSigns(const Eigen::MatrixBase<T2>& v, int legID);
#endif // LIBBIOMIMETICS_QUADRUPED_H