-
Notifications
You must be signed in to change notification settings - Fork 135
/
Copy pathpid.py
288 lines (242 loc) · 12.9 KB
/
pid.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
288
'''PID control class for Crazyflies.
Based on work conducted at UTIAS' DSL by SiQi Zhou and James Xu.
'''
import math
import os
import numpy as np
import pybullet as p
from scipy.spatial.transform import Rotation
from safe_control_gym.controllers.base_controller import BaseController
from safe_control_gym.envs.benchmark_env import Environment, Task
class PID(BaseController):
'''PID Class.'''
def __init__(self,
env_func=None,
g: float = 9.8,
kf: float = 3.16e-10,
km: float = 7.94e-12,
p_coeff_for=np.array([.4, .4, 1.25]),
i_coeff_for=np.array([.05, .05, .05]),
d_coeff_for=np.array([.2, .2, .5]),
p_coeff_tor=np.array([70000., 70000., 60000.]),
i_coeff_tor=np.array([.0, .0, 500.]),
d_coeff_tor=np.array([20000., 20000., 12000.]),
pwm2rpm_scale: float = 0.2685,
pwm2rpm_const: float = 4070.3,
min_pwm: float = 20000,
max_pwm: float = 65535,
**kwargs
):
'''Common control classes __init__ method.
Args:
g (float, optional): The gravitational acceleration in m/s^2.
kf (float, optional): Thrust coefficient.
km (float, optional): Torque coefficient.
p_coeff_for (ndarray, optional): Position proportional coefficients.
i_coeff_for (ndarray, optional): Position integral coefficients.
d_coeff_for (ndarray, optional): Position derivative coefficients.
p_coeff_tor (ndarray, optional): Attitude proportional coefficients.
i_coeff_tor (ndarray, optional): Attitude integral coefficients.
d_coeff_tor (ndarray, optional): Attitude derivative coefficients.
pwm2rpm_scale (float, optional): PWM-to-RPM scale factor.
pwm2rpm_const (float, optional): PWM-to-RPM constant factor.
min_pwm (float, optional): Minimum PWM.
max_pwm (float, optional): Maximum PWM.
'''
super().__init__(env_func, **kwargs)
self.env = env_func()
if self.env.NAME != Environment.QUADROTOR:
raise NotImplementedError('[ERROR] PID not implemented for any system other than Quadrotor (2D and 3D).')
self.env.reset()
self.g = g
self.KF = kf
self.KM = km
self.P_COEFF_FOR = np.array(p_coeff_for)
self.I_COEFF_FOR = np.array(i_coeff_for)
self.D_COEFF_FOR = np.array(d_coeff_for)
self.P_COEFF_TOR = np.array(p_coeff_tor)
self.I_COEFF_TOR = np.array(i_coeff_tor)
self.D_COEFF_TOR = np.array(d_coeff_tor)
self.PWM2RPM_SCALE = np.array(pwm2rpm_scale)
self.PWM2RPM_CONST = np.array(pwm2rpm_const)
self.MIN_PWM = np.array(min_pwm)
self.MAX_PWM = np.array(max_pwm)
self.MIXER_MATRIX = np.array([[.5, -.5, -1], [.5, .5, 1], [-.5, .5, -1], [-.5, -.5, 1]])
self.control_timestep = self.env.CTRL_TIMESTEP
self.reference = self.env.X_GOAL
self.reset()
def select_action(self, obs, info=None):
'''Determine the action to take at the current timestep.
Args:
obs (ndarray): The observation at this timestep.
info (dict): The info at this timestep.
Returns:
action (ndarray): The action chosen by the controller.
'''
step = self.extract_step(info)
# Step the environment and print all returned information.
if self.env.QUAD_TYPE == 2:
cur_pos = np.array([obs[0], 0, obs[2]])
cur_quat = np.array(p.getQuaternionFromEuler([0, obs[4], 0]))
cur_vel = np.array([obs[1], 0, obs[3]])
elif self.env.QUAD_TYPE == 3:
cur_pos = np.array([obs[0], obs[2], obs[4]])
cur_quat = np.array(p.getQuaternionFromEuler([obs[6], obs[7], obs[8]]))
cur_vel = np.array([obs[1], obs[3], obs[5]])
if self.env.QUAD_TYPE == 2:
if self.env.TASK == Task.TRAJ_TRACKING:
target_pos = np.array([self.reference[step, 0],
0,
self.reference[step, 2]])
target_vel = np.array([self.reference[step, 1],
0,
self.reference[step, 3]])
elif self.env.TASK == Task.STABILIZATION:
target_pos = np.array([self.reference[0], 0, self.reference[2]])
target_vel = np.array([0, 0, 0])
elif self.env.QUAD_TYPE == 3:
if self.env.TASK == Task.TRAJ_TRACKING:
target_pos = np.array([self.reference[step, 0],
self.reference[step, 2],
self.reference[step, 4]])
target_vel = np.array([self.reference[step, 1],
self.reference[step, 3],
self.reference[step, 5]])
elif self.env.TASK == Task.STABILIZATION:
target_pos = np.array([self.reference[0], self.reference[2], self.reference[4]])
target_vel = np.array([0, 0, 0])
target_rpy = np.zeros(3)
target_rpy_rates = np.zeros(3)
# Compute the next action.
thrust, computed_target_rpy, _ = self._dslPIDPositionControl(cur_pos,
cur_quat,
cur_vel,
target_pos,
target_rpy,
target_vel
)
rpm = self._dslPIDAttitudeControl(thrust,
cur_quat,
computed_target_rpy,
target_rpy_rates
)
action = rpm
action = self.KF * action**2
if self.env.QUAD_TYPE == 2:
action = np.array([action[0] + action[3], action[1] + action[2]])
return action
def _dslPIDPositionControl(self,
cur_pos,
cur_quat,
cur_vel,
target_pos,
target_rpy,
target_vel
):
'''DSL's CF2.x PID position control.
Args:
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:
thrust (float): The target thrust along the drone z-axis.
target_euler (ndarray): (3,1)-shaped array of floats containing the target roll, pitch, and yaw.
pos_e (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 * self.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):
raise ValueError('\n[ERROR] ctrl it', self.control_counter, 'in Control._dslPIDPositionControl(), values outside range [-pi,pi]')
return thrust, target_euler, pos_e
def _dslPIDAttitudeControl(self,
thrust,
cur_quat,
target_euler,
target_rpy_rates
):
'''DSL's CF2.x PID attitude control.
Args:
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:
rpm (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) / self.control_timestep
self.last_rpy = cur_rpy
self.integral_rpy_e = self.integral_rpy_e - rot_e * self.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 reset(self):
'''Resets the control classes. The previous step's and integral
errors for both position and attitude are set to zero.
'''
self.model = self.get_prior(self.env, self.prior_info)
self.GRAVITY = self.g * self.model.quad_mass # The gravitational force (g*M) acting on each drone.
self.env.reset()
self.reset_before_run()
def reset_before_run(self, obs=None, info=None, env=None):
'''Reinitialize just the controller before a new run.
Args:
obs (ndarray): The initial observation for the new run.
info (dict): The first info of the new run.
env (BenchmarkEnv): The environment to be used for the new run.
'''
# Clear PID control variables.
self.integral_pos_e = np.zeros(3)
self.last_rpy = np.zeros(3)
self.integral_rpy_e = np.zeros(3)
self.setup_results_dict()
def close(self):
'''Shuts down and cleans up lingering resources.'''
self.env.close()
def save(self, path):
'''Saves integral errors to checkpoint path.
Args:
path (str): The path where to the saved integral errors.
'''
path_dir = os.path.dirname(path)
os.makedirs(path_dir, exist_ok=True)
np.save(path, (self.integral_pos_e, self.last_rpy, self.integral_rpy_e))
def load(self, path):
'''Restores integral errors given checkpoint path.
Args:
path (str): The path where the integral errors are saved.
'''
self.integral_pos_e, self.last_rpy, self.integral_rpy_e = np.load(path)