-
Notifications
You must be signed in to change notification settings - Fork 338
/
VelocityAviary.py
229 lines (189 loc) · 9.92 KB
/
VelocityAviary.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
import os
import numpy as np
from gym import spaces
from gym_pybullet_drones.envs.BaseAviary import BaseAviary
from gym_pybullet_drones.utils.enums import DroneModel, Physics
from gym_pybullet_drones.control.DSLPIDControl import DSLPIDControl
from gym_pybullet_drones.control.SimplePIDControl import SimplePIDControl
class VelocityAviary(BaseAviary):
"""Multi-drone environment class for high-level planning."""
################################################################################
def __init__(self,
drone_model: DroneModel=DroneModel.CF2X,
num_drones: int=1,
neighbourhood_radius: float=np.inf,
initial_xyzs=None,
initial_rpys=None,
physics: Physics=Physics.PYB,
freq: int=240,
aggregate_phy_steps: int=1,
gui=False,
record=False,
obstacles=False,
user_debug_gui=True,
output_folder='results'
):
"""Initialization of an aviary environment for or high-level planning.
Parameters
----------
drone_model : DroneModel, optional
The desired drone type (detailed in an .urdf file in folder `assets`).
num_drones : int, optional
The desired number of drones in the aviary.
neighbourhood_radius : float, optional
Radius used to compute the drones' adjacency matrix, in meters.
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/`.
obstacles : bool, optional
Whether to add obstacles to the simulation.
user_debug_gui : bool, optional
Whether to draw the drones' axes and the GUI RPMs sliders.
"""
#### Create integrated controllers #########################
os.environ['KMP_DUPLICATE_LIB_OK']='True'
if drone_model in [DroneModel.CF2X, DroneModel.CF2P]:
self.ctrl = [DSLPIDControl(drone_model=DroneModel.CF2X) for i in range(num_drones)]
elif drone_model == DroneModel.HB:
raise ValueError("[ERROR] in VelocityAviary.__init__(), velocity control not supported for DroneModel.HB.")
super().__init__(drone_model=drone_model,
num_drones=num_drones,
neighbourhood_radius=neighbourhood_radius,
initial_xyzs=initial_xyzs,
initial_rpys=initial_rpys,
physics=physics,
freq=freq,
aggregate_phy_steps=aggregate_phy_steps,
gui=gui,
record=record,
obstacles=obstacles,
user_debug_gui=user_debug_gui,
output_folder=output_folder
)
#### Set a limit on the maximum target speed ###############
self.SPEED_LIMIT = 0.03 * self.MAX_SPEED_KMH * (1000/3600)
################################################################################
def _actionSpace(self):
"""Returns the action space of the environment.
Returns
-------
dict[str, ndarray]
A Dict of Box(4,) with NUM_DRONES entries,
indexed by drone Id in string format.
"""
#### Action vector ######### X Y Z fract. of MAX_SPEED_KMH
act_lower_bound = np.array([-1, -1, -1, 0])
act_upper_bound = np.array([ 1, 1, 1, 1])
return spaces.Dict({str(i): spaces.Box(low=act_lower_bound,
high=act_upper_bound,
dtype=np.float32
) for i in range(self.NUM_DRONES)})
################################################################################
def _observationSpace(self):
"""Returns the observation space of the environment.
Returns
-------
dict[str, dict[str, ndarray]]
A Dict with NUM_DRONES entries indexed by Id in string format,
each a Dict in the form {Box(20,), MultiBinary(NUM_DRONES)}.
"""
#### Observation vector ### X Y Z Q1 Q2 Q3 Q4 R P Y VX VY VZ WX WY WZ P0 P1 P2 P3
obs_lower_bound = np.array([-np.inf, -np.inf, 0., -1., -1., -1., -1., -np.pi, -np.pi, -np.pi, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf, 0., 0., 0., 0.])
obs_upper_bound = np.array([np.inf, np.inf, np.inf, 1., 1., 1., 1., np.pi, np.pi, np.pi, np.inf, np.inf, np.inf, np.inf, np.inf, np.inf, self.MAX_RPM, self.MAX_RPM, self.MAX_RPM, self.MAX_RPM])
return spaces.Dict({str(i): spaces.Dict({"state": spaces.Box(low=obs_lower_bound,
high=obs_upper_bound,
dtype=np.float32
),
"neighbors": spaces.MultiBinary(self.NUM_DRONES)
}) for i in range(self.NUM_DRONES)})
################################################################################
def _computeObs(self):
"""Returns the current observation of the environment.
For the value of key "state", see the implementation of `_getDroneStateVector()`,
the value of key "neighbors" is the drone's own row of the adjacency matrix.
Returns
-------
dict[str, dict[str, ndarray]]
A Dict with NUM_DRONES entries indexed by Id in string format,
each a Dict in the form {Box(20,), MultiBinary(NUM_DRONES)}.
"""
adjacency_mat = self._getAdjacencyMatrix()
return {str(i): {"state": self._getDroneStateVector(i), "neighbors": adjacency_mat[i, :]} for i in range(self.NUM_DRONES)}
################################################################################
def _preprocessAction(self,
action
):
"""Pre-processes the action passed to `.step()` into motors' RPMs.
Uses PID control to target a desired velocity vector.
Converts a dictionary into a 2D array.
Parameters
----------
action : dict[str, ndarray]
The desired velocity input for each drone, to be translated into RPMs.
Returns
-------
ndarray
(NUM_DRONES, 4)-shaped array of ints containing to clipped RPMs
commanded to the 4 motors of each drone.
"""
rpm = np.zeros((self.NUM_DRONES, 4))
for k, v in action.items():
#### Get the current state of the drone ###################
state = self._getDroneStateVector(int(k))
#### Normalize the first 3 components of the target velocity
if np.linalg.norm(v[0:3]) != 0:
v_unit_vector = v[0:3] / np.linalg.norm(v[0:3])
else:
v_unit_vector = np.zeros(3)
temp, _, _ = self.ctrl[int(k)].computeControl(control_timestep=self.AGGR_PHY_STEPS*self.TIMESTEP,
cur_pos=state[0:3],
cur_quat=state[3:7],
cur_vel=state[10:13],
cur_ang_vel=state[13:16],
target_pos=state[0:3], # same as the current position
target_rpy=np.array([0,0,state[9]]), # keep current yaw
target_vel=self.SPEED_LIMIT * np.abs(v[3]) * v_unit_vector # target the desired velocity vector
)
rpm[int(k),:] = temp
return rpm
################################################################################
def _computeReward(self):
"""Computes the current reward value(s).
Unused as this subclass is not meant for reinforcement learning.
Returns
-------
int
Dummy value.
"""
return -1
################################################################################
def _computeDone(self):
"""Computes the current done value(s).
Unused as this subclass is not meant for reinforcement learning.
Returns
-------
bool
Dummy value.
"""
return False
################################################################################
def _computeInfo(self):
"""Computes the current info dict(s).
Unused as this subclass is not meant for reinforcement learning.
Returns
-------
dict[str, int]
Dummy value.
"""
return {"answer": 42} #### Calculated by the Deep Thought supercomputer in 7.5M years