-
Notifications
You must be signed in to change notification settings - Fork 367
/
TuneAviary.py
231 lines (190 loc) · 9.84 KB
/
TuneAviary.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
import numpy as np
from gym_pybullet_drones.utils.enums import DroneModel, Physics
from gym_pybullet_drones.envs.single_agent_rl.BaseSingleAgentAviary import ActionType, ObservationType, BaseSingleAgentAviary
class TuneAviary(BaseSingleAgentAviary):
"""Single agent RL problem: optimize PID coefficients."""
################################################################################
def __init__(self,
drone_model: DroneModel=DroneModel.CF2X,
initial_xyzs=None,
initial_rpys=None,
physics: Physics=Physics.PYB,
freq: int=240,
aggregate_phy_steps: int=1,
gui=False,
record=False,
obs: ObservationType=ObservationType.KIN,
act: ActionType=ActionType.TUN
):
"""Initialization of a single agent RL environment.
Using the generic single agent RL superclass.
Parameters
----------
drone_model : DroneModel, optional
The desired drone type (detailed in an .urdf file in folder `assets`).
initial_xyzs: ndarray | None, optional
(NUM_DRONES, 3)-shaped array containing the initial XYZ position of the drones.
initial_rpys: ndarray | None, optional
(NUM_DRONES, 3)-shaped array containing the initial orientations of the drones (in radians).
physics : Physics, optional
The desired implementation of PyBullet physics/custom dynamics.
freq : int, optional
The frequency (Hz) at which the physics engine steps.
aggregate_phy_steps : int, optional
The number of physics steps within one call to `BaseAviary.step()`.
gui : bool, optional
Whether to use PyBullet's GUI.
record : bool, optional
Whether to save a video of the simulation in folder `files/videos/`.
obs : ObservationType, optional
The type of observation space (kinematic information or vision)
act : ActionType, optional
The type of action space (1 or 3D; RPMS, thurst and torques, or waypoint with PID control)
"""
super().__init__(drone_model=drone_model,
initial_xyzs=initial_xyzs,
initial_rpys=initial_rpys,
physics=physics,
freq=freq,
aggregate_phy_steps=aggregate_phy_steps,
gui=gui,
record=record,
obs=obs,
act=act
)
if self.ACT_TYPE != ActionType.TUN:
print("[ERROR] in TuneAviary.__init__(), ACT_TYPE must be ActionType.TUN" )
exit()
#### Initialize the target trajectory ######################
self.TRAJ_STEPS = int((self.SIM_FREQ * self.EPISODE_LEN_SEC) / self.AGGR_PHY_STEPS)
self.CTRL_TIMESTEP = self.AGGR_PHY_STEPS*self.TIMESTEP
self.TARGET_POSITION = np.array([[0, 4.0*np.cos(0.006*i), 1.0] for i in range(self.TRAJ_STEPS)])
#### Derive the trajectory to obtain target velocity #######
self.TARGET_VELOCITY = np.zeros([self.TRAJ_STEPS, 3])
self.TARGET_VELOCITY[1:, :] = (self.TARGET_POSITION[1:, :] - self.TARGET_POSITION[0:-1, :]) / self.CTRL_TIMESTEP
################################################################################
def _trajectoryTrackingRPMs(self):
"""Computes the RPMs values to target a hardcoded trajectory.
Returns
-------
ndarray
(4,)-shaped array of ints containing to clipped RPMs
commanded to the 4 motors of each drone.
"""
####
state = self._getDroneStateVector(0)
i = min(int(self.step_counter / self.AGGR_PHY_STEPS), self.TRAJ_STEPS - 1)
rpm, _, _ = self.ctrl.computeControl(control_timestep=self.CTRL_TIMESTEP,
cur_pos=state[0:3],
cur_quat=state[3:7],
cur_vel=state[10:13],
cur_ang_vel=state[13:16],
target_pos=self.TARGET_POSITION[i, :],
target_vel=self.TARGET_VELOCITY[i, :]
)
return rpm
################################################################################
def _computeReward(self):
"""Computes the current reward value.
Returns
-------
float
The reward.
"""
state = self._getDroneStateVector(0)
i = min(int(self.step_counter / self.AGGR_PHY_STEPS), self.TRAJ_STEPS - 1)
return -1 * np.linalg.norm(self.TARGET_POSITION[i, :]-state[0:3])**2
################################################################################
def _computeDone(self):
"""Computes the current done value.
Returns
-------
bool
Whether the current episode is done.
"""
if self.step_counter/self.SIM_FREQ > self.EPISODE_LEN_SEC:
return True
else:
return False
################################################################################
def _computeInfo(self):
"""Computes the current info dict(s).
Unused.
Returns
-------
dict[str, int]
Dummy value.
"""
return {"answer": 42} #### Calculated by the Deep Thought supercomputer in 7.5M years
################################################################################
def _clipAndNormalizeState(self,
state
):
"""Normalizes a drone's state to the [-1,1] range.
Parameters
----------
state : ndarray
(20,)-shaped array of floats containing the non-normalized state of a single drone.
Returns
-------
ndarray
(20,)-shaped array of floats containing the normalized state of a single drone.
"""
MAX_LIN_VEL_XY = 3
MAX_LIN_VEL_Z = 1
MAX_XY = MAX_LIN_VEL_XY*self.EPISODE_LEN_SEC
MAX_Z = MAX_LIN_VEL_Z*self.EPISODE_LEN_SEC
MAX_PITCH_ROLL = np.pi # Full range
clipped_pos_xy = np.clip(state[0:2], -MAX_XY, MAX_XY)
clipped_pos_z = np.clip(state[2], 0, MAX_Z)
clipped_rp = np.clip(state[7:9], -MAX_PITCH_ROLL, MAX_PITCH_ROLL)
clipped_vel_xy = np.clip(state[10:12], -MAX_LIN_VEL_XY, MAX_LIN_VEL_XY)
clipped_vel_z = np.clip(state[12], -MAX_LIN_VEL_Z, MAX_LIN_VEL_Z)
if self.GUI:
self._clipAndNormalizeStateWarning(state,
clipped_pos_xy,
clipped_pos_z,
clipped_rp,
clipped_vel_xy,
clipped_vel_z
)
normalized_pos_xy = clipped_pos_xy / MAX_XY
normalized_pos_z = clipped_pos_z / MAX_Z
normalized_rp = clipped_rp / MAX_PITCH_ROLL
normalized_y = state[9] / np.pi # No reason to clip
normalized_vel_xy = clipped_vel_xy / MAX_LIN_VEL_XY
normalized_vel_z = clipped_vel_z / MAX_LIN_VEL_XY
normalized_ang_vel = state[13:16]/np.linalg.norm(state[13:16]) if np.linalg.norm(state[13:16]) != 0 else state[13:16]
norm_and_clipped = np.hstack([normalized_pos_xy,
normalized_pos_z,
state[3:7],
normalized_rp,
normalized_y,
normalized_vel_xy,
normalized_vel_z,
normalized_ang_vel,
state[16:20]
]).reshape(20,)
return norm_and_clipped
################################################################################
def _clipAndNormalizeStateWarning(self,
state,
clipped_pos_xy,
clipped_pos_z,
clipped_rp,
clipped_vel_xy,
clipped_vel_z,
):
"""Debugging printouts associated to `_clipAndNormalizeState`.
Print a warning if values in a state vector is out of the clipping range.
"""
if not(clipped_pos_xy == np.array(state[0:2])).all():
print("[WARNING] it", self.step_counter, "in TuneAviary._clipAndNormalizeState(), clipped xy position [{:.2f} {:.2f}]".format(state[0], state[1]))
if not(clipped_pos_z == np.array(state[2])).all():
print("[WARNING] it", self.step_counter, "in TuneAviary._clipAndNormalizeState(), clipped z position [{:.2f}]".format(state[2]))
if not(clipped_rp == np.array(state[7:9])).all():
print("[WARNING] it", self.step_counter, "in TuneAviary._clipAndNormalizeState(), clipped roll/pitch [{:.2f} {:.2f}]".format(state[7], state[8]))
if not(clipped_vel_xy == np.array(state[10:12])).all():
print("[WARNING] it", self.step_counter, "in TuneAviary._clipAndNormalizeState(), clipped xy velocity [{:.2f} {:.2f}]".format(state[10], state[11]))
if not(clipped_vel_z == np.array(state[12])).all():
print("[WARNING] it", self.step_counter, "in TuneAviary._clipAndNormalizeState(), clipped z velocity [{:.2f}]".format(state[12]))