forked from Nate711/PupperPythonSim
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathPupperConfig.py
More file actions
278 lines (223 loc) · 7.58 KB
/
Copy pathPupperConfig.py
File metadata and controls
278 lines (223 loc) · 7.58 KB
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
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
import numpy as np
from scipy.linalg import solve
from src.RobotConfig import MICROS_PER_RAD, NEUTRAL_ANGLE_DEGREES
from enum import Enum
class UserInputParams:
def __init__(self):
self.max_x_velocity = 0.5
self.max_y_velocity = 0.24
self.max_yaw_rate = 0.2
self.max_pitch = 30.0 * np.pi / 180.0
class PWMParams:
def __init__(self):
self.pins = np.array([[2, 14, 18, 23], [3, 15, 27, 24], [4, 17, 22, 25]])
self.range = 4000
self.freq = 250
class ServoParams:
def __init__(self):
self.neutral_position_pwm = 1500 # Middle position
self.micros_per_rad = MICROS_PER_RAD # Must be calibrated
# The neutral angle of the joint relative to the modeled zero-angle in degrees, for each joint
self.neutral_angle_degrees = NEUTRAL_ANGLE_DEGREES
self.servo_multipliers = np.array(
[[1, 1, 1, 1], [-1, 1, -1, 1], [1, -1, 1, -1]]
)
@property
def neutral_angles(self):
return self.neutral_angle_degrees * np.pi / 180.0 # Convert to radians
class BehaviorState(Enum):
REST = 0
TROT = 1
HOP = 2
FINISHHOP = 3
class MovementCommand:
"""Stores movement command
"""
def __init__(self):
self.v_xy_ref = np.array([0, 0])
self.wz_ref = 0.0
self.z_ref = -0.16
class MovementReference:
"""Stores movement reference
"""
def __init__(self):
self.v_xy_ref = np.array([0, 0])
self.wz_ref = 0.0
self.z_ref = -0.16
self.pitch = 0.0
self.roll = 0.0
class StanceParams:
"""Stance parameters
"""
def __init__(self):
self.z_time_constant = 0.02
self.z_speed = 0.03 # maximum speed [m/s]
self.pitch_deadband = 0.02
self.pitch_time_constant = 0.25
self.max_pitch_rate = 0.15
self.roll_speed = 0.16 # maximum roll rate [rad/s]
self.delta_x = 0.1
self.delta_y = 0.10
self.x_shift = -0.01
@property
def default_stance(self):
return np.array(
[
[
self.delta_x + self.x_shift,
self.delta_x + self.x_shift,
-self.delta_x + self.x_shift,
-self.delta_x + self.x_shift,
],
[-self.delta_y, self.delta_y, -self.delta_y, self.delta_y],
[0, 0, 0, 0],
]
)
class SwingParams:
"""Swing Parameters
"""
def __init__(self):
self.z_coeffs = None
self.z_clearance = 0.05
self.alpha = (
0.5 # Ratio between touchdown distance and total horizontal stance movement
)
self.beta = (
0.5 # Ratio between touchdown distance and total horizontal stance movement
)
@property
def z_clearance(self):
return self.__z_clearance
@z_clearance.setter
def z_clearance(self, z):
self.__z_clearance = z
b_z = np.array([0, 0, 0, 0, self.__z_clearance])
A_z = np.array(
[
[0, 0, 0, 0, 1],
[1, 1, 1, 1, 1],
[0, 0, 0, 1, 0],
[4, 3, 2, 1, 0],
[0.5 ** 4, 0.5 ** 3, 0.5 ** 2, 0.5 ** 1, 0.5 ** 0],
]
)
self.z_coeffs = solve(A_z, b_z)
class GaitParams:
"""Gait Parameters
"""
def __init__(self):
self.dt = 0.01
self.num_phases = 4
self.contact_phases = np.array(
[[1, 1, 1, 0],
[1, 0, 1, 1],
[1, 0, 1, 1],
[1, 1, 1, 0]]
)
self.overlap_time = (
0.10 # duration of the phase where all four feet are on the ground
)
self.swing_time = (
0.20 # duration of the phase when only two feet are on the ground
)
@property
def overlap_ticks(self):
return int(self.overlap_time / self.dt)
@property
def swing_ticks(self):
return int(self.swing_time / self.dt)
@property
def stance_ticks(self):
return 2 * self.overlap_ticks + self.swing_ticks
@property
def phase_times(self):
return np.array(
[self.overlap_ticks, self.swing_ticks, self.overlap_ticks, self.swing_ticks]
)
@property
def phase_length(self):
return 2 * self.overlap_ticks + 2 * self.swing_ticks
class PupperConfig:
"""Pupper hardware parameters
"""
def __init__(self):
# XML files
self.XML_IN = "pupper.xml"
self.XML_OUT = "pupper_out.xml"
# Robot geometry
self.LEG_FB = 0.10 # front-back distance from center line to leg axis
self.LEG_LR = 0.04 # left-right distance from center line to leg plane
self.LEG_L2 = 0.115
self.LEG_L1 = 0.1235
self.ABDUCTION_OFFSET = 0.03 # distance from abduction axis to leg
self.FOOT_RADIUS = 0.01
self.HIP_L = 0.0394
self.HIP_W = 0.0744
self.HIP_T = 0.0214
self.HIP_OFFSET = 0.0132
self.L = 0.276
self.W = 0.100
self.T = 0.050
self.LEG_ORIGINS = np.array(
[
[self.LEG_FB, self.LEG_FB, -self.LEG_FB, -self.LEG_FB],
[-self.LEG_LR, self.LEG_LR, -self.LEG_LR, self.LEG_LR],
[0, 0, 0, 0],
]
)
self.ABDUCTION_OFFSETS = np.array(
[
-self.ABDUCTION_OFFSET,
self.ABDUCTION_OFFSET,
-self.ABDUCTION_OFFSET,
self.ABDUCTION_OFFSET,
]
)
self.START_HEIGHT = 0.3
# Robot inertia params
self.FRAME_MASS = 0.560 # kg
self.MODULE_MASS = 0.080 # kg
self.LEG_MASS = 0.030 # kg
self.MASS = self.FRAME_MASS + (self.MODULE_MASS + self.LEG_MASS) * 4
# Compensation factor of 3 because the inertia measurement was just
# of the carbon fiber and plastic parts of the frame and did not
# include the hip servos and electronics
self.FRAME_INERTIA = tuple(
map(lambda x: 3.0 * x, (1.844e-4, 1.254e-3, 1.337e-3))
)
self.MODULE_INERTIA = (3.698e-5, 7.127e-6, 4.075e-5)
leg_z = 1e-6
leg_mass = 0.010
leg_x = 1 / 12 * self.LEG_L1 ** 2 * leg_mass
leg_y = leg_x
self.LEG_INERTIA = (leg_x, leg_y, leg_z)
# Joint params
G = 220 # Servo gear ratio
m_rotor = 0.016 # Servo rotor mass
r_rotor = 0.005 # Rotor radius
self.ARMATURE = G ** 2 * m_rotor * r_rotor ** 2 # Inertia of rotational joints
# print("Servo armature", self.ARMATURE)
NATURAL_DAMPING = 1.0 # Damping resulting from friction
ELECTRICAL_DAMPING = 0.049 # Damping resulting from back-EMF
self.REV_DAMPING = (
NATURAL_DAMPING + ELECTRICAL_DAMPING
) # Damping torque on the revolute joints
# Servo params
self.SERVO_REV_KP = 300 # Position gain [Nm/rad]
# Force limits
self.MAX_JOINT_TORQUE = 3.0
self.REVOLUTE_RANGE = 1.57
class EnvironmentConfig:
"""Environmental parameters
"""
def __init__(self):
self.MU = 1.5 # coeff friction
self.DT = 0.001 # seconds between simulation steps
class SolverConfig:
"""MuJoCo solver parameters
"""
def __init__(self):
self.JOINT_SOLREF = "0.001 1" # time constant and damping ratio for joints
self.JOINT_SOLIMP = "0.9 0.95 0.001" # joint constraint parameters
self.GEOM_SOLREF = "0.01 1" # time constant and damping ratio for geom contacts
self.GEOM_SOLIMP = "0.9 0.95 0.001" # geometry contact parameters