-
Notifications
You must be signed in to change notification settings - Fork 371
/
DSLPIDControl.py
287 lines (254 loc) · 12.7 KB
/
DSLPIDControl.py
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
279
280
281
282
283
284
285
286
287
import math
import numpy as np
import pybullet as p
from scipy.spatial.transform import Rotation
from gym_pybullet_drones.control.BaseControl import BaseControl
from gym_pybullet_drones.utils.enums import DroneModel
class DSLPIDControl(BaseControl):
"""PID control class for Crazyflies.
Based on work conducted at UTIAS' DSL. Contributors: SiQi Zhou, James Xu,
Tracy Du, Mario Vukosavljev, Calvin Ngan, and Jingyuan Hou.
"""
################################################################################
def __init__(self,
drone_model: DroneModel,
g: float=9.8
):
"""Common control classes __init__ method.
Parameters
----------
drone_model : DroneModel
The type of drone to control (detailed in an .urdf file in folder `assets`).
g : float, optional
The gravitational acceleration in m/s^2.
"""
super().__init__(drone_model=drone_model, g=g)
if self.DRONE_MODEL != DroneModel.CF2X and self.DRONE_MODEL != DroneModel.CF2P:
print("[ERROR] in DSLPIDControl.__init__(), DSLPIDControl requires DroneModel.CF2X or DroneModel.CF2P")
exit()
self.P_COEFF_FOR = np.array([.4, .4, 1.25])
self.I_COEFF_FOR = np.array([.05, .05, .05])
self.D_COEFF_FOR = np.array([.2, .2, .5])
self.P_COEFF_TOR = np.array([70000., 70000., 60000.])
self.I_COEFF_TOR = np.array([.0, .0, 500.])
self.D_COEFF_TOR = np.array([20000., 20000., 12000.])
self.PWM2RPM_SCALE = 0.2685
self.PWM2RPM_CONST = 4070.3
self.MIN_PWM = 20000
self.MAX_PWM = 65535
if self.DRONE_MODEL == DroneModel.CF2X:
self.MIXER_MATRIX = np.array([
[-.5, -.5, -1],
[-.5, .5, 1],
[.5, .5, -1],
[.5, -.5, 1]
])
elif self.DRONE_MODEL == DroneModel.CF2P:
self.MIXER_MATRIX = np.array([
[0, -1, -1],
[+1, 0, 1],
[0, 1, -1],
[-1, 0, 1]
])
self.reset()
################################################################################
def reset(self):
"""Resets the control classes.
The previous step's and integral errors for both position and attitude are set to zero.
"""
super().reset()
#### Store the last roll, pitch, and yaw ###################
self.last_rpy = np.zeros(3)
#### Initialized PID control variables #####################
self.last_pos_e = np.zeros(3)
self.integral_pos_e = np.zeros(3)
self.last_rpy_e = np.zeros(3)
self.integral_rpy_e = np.zeros(3)
################################################################################
def computeControl(self,
control_timestep,
cur_pos,
cur_quat,
cur_vel,
cur_ang_vel,
target_pos,
target_rpy=np.zeros(3),
target_vel=np.zeros(3),
target_rpy_rates=np.zeros(3)
):
"""Computes the PID control action (as RPMs) for a single drone.
This methods sequentially calls `_dslPIDPositionControl()` and `_dslPIDAttitudeControl()`.
Parameter `cur_ang_vel` is unused.
Parameters
----------
control_timestep : float
The time step at which control is computed.
cur_pos : ndarray
(3,1)-shaped array of floats containing the current position.
cur_quat : ndarray
(4,1)-shaped array of floats containing the current orientation as a quaternion.
cur_vel : ndarray
(3,1)-shaped array of floats containing the current velocity.
cur_ang_vel : ndarray
(3,1)-shaped array of floats containing the current angular velocity.
target_pos : ndarray
(3,1)-shaped array of floats containing the desired position.
target_rpy : ndarray, optional
(3,1)-shaped array of floats containing the desired orientation as roll, pitch, yaw.
target_vel : ndarray, optional
(3,1)-shaped array of floats containing the desired velocity.
target_rpy_rates : ndarray, optional
(3,1)-shaped array of floats containing the desired roll, pitch, and yaw rates.
Returns
-------
ndarray
(4,1)-shaped array of integers containing the RPMs to apply to each of the 4 motors.
ndarray
(3,1)-shaped array of floats containing the current XYZ position error.
float
The current yaw error.
"""
self.control_counter += 1
thrust, computed_target_rpy, pos_e = self._dslPIDPositionControl(control_timestep,
cur_pos,
cur_quat,
cur_vel,
target_pos,
target_rpy,
target_vel
)
rpm = self._dslPIDAttitudeControl(control_timestep,
thrust,
cur_quat,
computed_target_rpy,
target_rpy_rates
)
cur_rpy = p.getEulerFromQuaternion(cur_quat)
return rpm, pos_e, computed_target_rpy[2] - cur_rpy[2]
################################################################################
def _dslPIDPositionControl(self,
control_timestep,
cur_pos,
cur_quat,
cur_vel,
target_pos,
target_rpy,
target_vel
):
"""DSL's CF2.x PID position control.
Parameters
----------
control_timestep : float
The time step at which control is computed.
cur_pos : ndarray
(3,1)-shaped array of floats containing the current position.
cur_quat : ndarray
(4,1)-shaped array of floats containing the current orientation as a quaternion.
cur_vel : ndarray
(3,1)-shaped array of floats containing the current velocity.
target_pos : ndarray
(3,1)-shaped array of floats containing the desired position.
target_rpy : ndarray
(3,1)-shaped array of floats containing the desired orientation as roll, pitch, yaw.
target_vel : ndarray
(3,1)-shaped array of floats containing the desired velocity.
Returns
-------
float
The target thrust along the drone z-axis.
ndarray
(3,1)-shaped array of floats containing the target roll, pitch, and yaw.
float
The current position error.
"""
cur_rotation = np.array(p.getMatrixFromQuaternion(cur_quat)).reshape(3, 3)
pos_e = target_pos - cur_pos
vel_e = target_vel - cur_vel
self.integral_pos_e = self.integral_pos_e + pos_e*control_timestep
self.integral_pos_e = np.clip(self.integral_pos_e, -2., 2.)
self.integral_pos_e[2] = np.clip(self.integral_pos_e[2], -0.15, .15)
#### PID target thrust #####################################
target_thrust = np.multiply(self.P_COEFF_FOR, pos_e) \
+ np.multiply(self.I_COEFF_FOR, self.integral_pos_e) \
+ np.multiply(self.D_COEFF_FOR, vel_e) + np.array([0, 0, self.GRAVITY])
scalar_thrust = max(0., np.dot(target_thrust, cur_rotation[:,2]))
thrust = (math.sqrt(scalar_thrust / (4*self.KF)) - self.PWM2RPM_CONST) / self.PWM2RPM_SCALE
target_z_ax = target_thrust / np.linalg.norm(target_thrust)
target_x_c = np.array([math.cos(target_rpy[2]), math.sin(target_rpy[2]), 0])
target_y_ax = np.cross(target_z_ax, target_x_c) / np.linalg.norm(np.cross(target_z_ax, target_x_c))
target_x_ax = np.cross(target_y_ax, target_z_ax)
target_rotation = (np.vstack([target_x_ax, target_y_ax, target_z_ax])).transpose()
#### Target rotation #######################################
target_euler = (Rotation.from_matrix(target_rotation)).as_euler('XYZ', degrees=False)
if np.any(np.abs(target_euler) > math.pi):
print("\n[ERROR] ctrl it", self.control_counter, "in Control._dslPIDPositionControl(), values outside range [-pi,pi]")
return thrust, target_euler, pos_e
################################################################################
def _dslPIDAttitudeControl(self,
control_timestep,
thrust,
cur_quat,
target_euler,
target_rpy_rates
):
"""DSL's CF2.x PID attitude control.
Parameters
----------
control_timestep : float
The time step at which control is computed.
thrust : float
The target thrust along the drone z-axis.
cur_quat : ndarray
(4,1)-shaped array of floats containing the current orientation as a quaternion.
target_euler : ndarray
(3,1)-shaped array of floats containing the computed target Euler angles.
target_rpy_rates : ndarray
(3,1)-shaped array of floats containing the desired roll, pitch, and yaw rates.
Returns
-------
ndarray
(4,1)-shaped array of integers containing the RPMs to apply to each of the 4 motors.
"""
cur_rotation = np.array(p.getMatrixFromQuaternion(cur_quat)).reshape(3, 3)
cur_rpy = np.array(p.getEulerFromQuaternion(cur_quat))
target_quat = (Rotation.from_euler('XYZ', target_euler, degrees=False)).as_quat()
w,x,y,z = target_quat
target_rotation = (Rotation.from_quat([w, x, y, z])).as_matrix()
rot_matrix_e = np.dot((target_rotation.transpose()),cur_rotation) - np.dot(cur_rotation.transpose(),target_rotation)
rot_e = np.array([rot_matrix_e[2, 1], rot_matrix_e[0, 2], rot_matrix_e[1, 0]])
rpy_rates_e = target_rpy_rates - (cur_rpy - self.last_rpy)/control_timestep
self.last_rpy = cur_rpy
self.integral_rpy_e = self.integral_rpy_e - rot_e*control_timestep
self.integral_rpy_e = np.clip(self.integral_rpy_e, -1500., 1500.)
self.integral_rpy_e[0:2] = np.clip(self.integral_rpy_e[0:2], -1., 1.)
#### PID target torques ####################################
target_torques = - np.multiply(self.P_COEFF_TOR, rot_e) \
+ np.multiply(self.D_COEFF_TOR, rpy_rates_e) \
+ np.multiply(self.I_COEFF_TOR, self.integral_rpy_e)
target_torques = np.clip(target_torques, -3200, 3200)
pwm = thrust + np.dot(self.MIXER_MATRIX, target_torques)
pwm = np.clip(pwm, self.MIN_PWM, self.MAX_PWM)
return self.PWM2RPM_SCALE * pwm + self.PWM2RPM_CONST
################################################################################
def _one23DInterface(self,
thrust
):
"""Utility function interfacing 1, 2, or 3D thrust input use cases.
Parameters
----------
thrust : ndarray
Array of floats of length 1, 2, or 4 containing a desired thrust input.
Returns
-------
ndarray
(4,1)-shaped array of integers containing the PWM (not RPMs) to apply to each of the 4 motors.
"""
DIM = len(np.array(thrust))
pwm = np.clip((np.sqrt(np.array(thrust)/(self.KF*(4/DIM)))-self.PWM2RPM_CONST)/self.PWM2RPM_SCALE, self.MIN_PWM, self.MAX_PWM)
if DIM in [1, 4]:
return np.repeat(pwm, 4/DIM)
elif DIM==2:
return np.hstack([pwm, np.flip(pwm)])
else:
print("[ERROR] in DSLPIDControl._one23DInterface()")
exit()