-
Notifications
You must be signed in to change notification settings - Fork 62
/
fwmav_sim_env.py
225 lines (174 loc) · 7.3 KB
/
fwmav_sim_env.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
########################## FWMAV Simulation #########################
# Version 0.3
# Fan Fei Feb 2019
# Direct motor driven flapping wing MAV simulation
#######################################################################
import gym
from gym.spaces import Box
import numpy as np
import json
from Flappy.envs.simulation import Simulation
from Flappy.envs.controllers.pid_controller import PIDController
from Flappy.envs.mission import Mission
class FWMAVSimEnv(gym.Env):
def __init__(self):
with open ('./Flappy/envs/config/sim_config.json') as file:
sim_config = json.load(file)
with open('./Flappy/envs/config/mav_config_list.json') as file:
mav_config_list = json.load(file)
self.sim = Simulation(mav_config_list, sim_config)
self.observation = np.zeros([18], dtype=np.float64)
self.observation_bound = np.array([
1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0,
1.0, 1.0, 1.0, 1.0, 1.0
])
self.action_lb = np.array([-5, -3, -3.5, -0.15])
self.action_ub = np.array([11, 3, 3.5, 0.15])
self.total_action_lb = np.array([0, -3, -3.5, -0.15])
self.total_action_ub = np.array([18.0, 3, 3.5, 0.15])
self.action_old = np.array([0, 0, 0, 0])
self.pid_policy = PIDController(self.sim.dt_c)
self.mission = Mission(self.pid_policy)
self.done = False
self.reward = 0
self.is_print = False
def enable_viz(self):
self.sim.enable_viz()
def enable_print(self):
self.is_print = True
def set_attack_type(self, attack_type):
self.attack_type = attack_type
@property
def observation_space(self):
return Box(np.array([-1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf, -np.inf]), np.array([1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, np.inf, np.inf, np.inf, np.inf, np.inf, np.inf, np.inf, np.inf, np.inf]))
@property
def action_space(self):
return Box(np.array([-5.0, -3, -3.5, -0.15]), np.array([11.0, 3, 3.5, 0.15]))
def reset(self):
rpy_limit = 0.785398 # 45 deg
pqr_limit = 3.14159 # 180 deg/s
xyz_limit = 0.1 # 10 cm
xyz_dot_limit = 0.1 # 10cm/s
positions = np.zeros([10,1], dtype=np.float64)
velocities = np.zeros([10,1], dtype=np.float64)
init_attitude = np.random.uniform(-rpy_limit, rpy_limit, size=(3,1))
init_angular_velocity = np.random.uniform(-pqr_limit, pqr_limit, size=(3,1))
init_position = np.random.uniform(-xyz_limit, xyz_limit, size=(3, 1))
init_body_velocity = np.random.uniform(-xyz_dot_limit, xyz_dot_limit, size=(3,1))
positions[0:3] = init_attitude
positions[3:6] = init_position
velocities[0:6] = np.concatenate((init_angular_velocity,init_body_velocity), axis = 0)
self.sim.reset()
self.sim.set_states(positions, velocities)
self.observation = self.get_observation()
self.next_control_time = self.sim.dt_c
self.mission.reset()
return self.observation
def seed(self, seed=0):
# np.random.seed(seed)
return
def step(self, action):
# scale action from [-1,1] to [action_lb, action_ub]
scaled_action = self.action_lb + \
(action + 1.) * 0.5 * (self.action_ub - self.action_lb)
scaled_action = np.clip(scaled_action, self.action_lb, self.action_ub)
self.mission.update_waypoint(self.sim.world.time())
action_pid = np.squeeze(
self.pid_policy.get_action(self.sim.states, self.sim.dt_c,
self.sim.sensor_fusion))
# input_signal = policy_action + pid_action
input_signal = np.clip(scaled_action + action_pid, self.total_action_lb, self.total_action_ub)
# run simulation and down sample from f_sim to f_control
while self.sim.world.time() < self.next_control_time:
self.sim.step(input_signal)
self.next_control_time += self.sim.dt_c
self.observation = self.get_observation()
reward = self.get_reward(action)
done = self.get_terminal()
return self.observation, reward, done, {}
def get_observation(self):
# define observations here3
#
# observations are the following
# rotation matrix
# positions
# linear velocities
# angular velocities
observation = np.zeros([18],dtype=np.float64)
# get full states
flapper1_states = self.sim.states
# create rotation matrix
roll_angle = flapper1_states['body_positions'][0]
pitch_angle = flapper1_states['body_positions'][1]
yaw_angle = flapper1_states['body_positions'][2]
R = self.euler_2_R(roll_angle, pitch_angle, yaw_angle)
observation[0:9] = R.reshape(-1)
# other states
observation[9] = flapper1_states['body_positions'][3] - self.mission.pos_target_x_ # special x
observation[10] = flapper1_states['body_positions'][4] - self.mission.pos_target_y_ # special y
observation[11] = flapper1_states['body_positions'][5] - self.mission.pos_target_z_ # special z
observation[12] = flapper1_states['body_spatial_velocities'][0] # spatial x_dot
observation[13] = flapper1_states['body_spatial_velocities'][1] # spatial y_dot
observation[14] = flapper1_states['body_spatial_velocities'][2] # spatial z_dot
observation[15] = flapper1_states['body_velocities'][0] # p
observation[16] = flapper1_states['body_velocities'][1] # q
observation[17] = flapper1_states['body_velocities'][2] # r
observation = observation/self.observation_bound
return observation
def get_reward(self, action):
reward = 0
flapper1_states = self.sim.states
position = flapper1_states['body_positions'][3:6]
position_target = np.array([self.mission.pos_target_x_,self.mission.pos_target_y_,self.mission.pos_target_z_])
position_error = position_target - position
angular_position = flapper1_states['body_positions'][0:3]
angular_position_target = np.array([[0.0], [0.0], [0.0]])
angular_position_error = angular_position_target - angular_position
linear_velocity = flapper1_states['body_spatial_velocities']
angular_velocity = flapper1_states['body_velocities'][0:3]
d_action = action - self.action_old
self.action_old = action
control_cost = 2e-4*np.sum(np.square(action))
d_control_cost = 2*np.sum(np.square(d_action))
position_cost = 4e-3*np.linalg.norm(position_error)
angular_position_cost = 8e-3*np.linalg.norm(angular_position_error)
velocity_cots = 5e-4*np.linalg.norm(linear_velocity)
angular_velocity_cost = 6e-4*np.linalg.norm(angular_velocity)
stability_cost = position_cost + angular_position_cost + velocity_cots + angular_velocity_cost
cost = stability_cost + control_cost + d_control_cost
reward = 1 / (cost**2 + 1e-6)
return reward
def get_terminal(self):
if self.sim.check_collision():
return True
if self.sim.world.time() > 20:
return True
flapper1_states = self.sim.states
x = flapper1_states['body_positions'][3]
y = flapper1_states['body_positions'][4]
z = flapper1_states['body_positions'][5]
distance = (x**2 + y**2 + z**2)**0.5
if distance > 1:
return True
return False
def euler_2_R(self, phi, theta, psi):
R = np.zeros([3, 3], dtype=np.float64)
C_phi = np.cos(phi)
S_phi = np.sin(phi)
C_theta = np.cos(theta)
S_theta = np.sin(theta)
C_psi = np.cos(psi)
S_psi = np.sin(psi)
R[0, 0] = C_psi * C_theta
R[0, 1] = C_psi * S_theta * C_phi - S_psi * C_phi
R[0, 2] = C_psi * S_theta * C_phi + S_psi * S_phi
R[1, 0] = S_psi * C_theta
R[1, 1] = S_psi * S_theta * S_phi + C_psi * C_phi
R[1, 2] = S_psi * S_theta * C_phi - C_psi * S_phi
R[2, 0] = -S_theta
R[2, 1] = C_theta * S_phi
R[2, 2] = C_theta * C_phi
return R
def render(self):
# self.sim.render()
return