Skip to content

Commit 4586689

Browse files
committed
working attitude controller for quad 2d
1 parent bfd0d31 commit 4586689

File tree

10 files changed

+255
-35
lines changed

10 files changed

+255
-35
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,56 @@
1+
task_config:
2+
seed: 1337
3+
info_in_reset: True
4+
ctrl_freq: 50
5+
pyb_freq: 1000
6+
gui: False
7+
physics: pyb
8+
quad_type: 5
9+
10+
init_state:
11+
init_x: 0
12+
init_x_dot: 0
13+
init_z: 1.15
14+
init_z_dot: 0
15+
init_theta: 0
16+
init_theta_dot: 0
17+
randomized_init: True
18+
randomized_inertial_prop: False
19+
20+
init_state_randomization_info:
21+
init_x:
22+
distrib: 'uniform'
23+
low: -0.01
24+
high: 0.01
25+
init_x_dot:
26+
distrib: 'uniform'
27+
low: -0.01
28+
high: 0.01
29+
init_z:
30+
distrib: 'uniform'
31+
low: -0.01
32+
high: 0.01
33+
init_z_dot:
34+
distrib: 'uniform'
35+
low: -0.01
36+
high: 0.01
37+
init_theta:
38+
distrib: 'uniform'
39+
low: -0.02
40+
high: 0.02
41+
init_theta_dot:
42+
distrib: 'uniform'
43+
low: -0.02
44+
high: 0.02
45+
46+
task: traj_tracking
47+
task_info:
48+
trajectory_type: figure8
49+
num_cycles: 1
50+
trajectory_plane: 'xz'
51+
trajectory_position_offset: [ 0, 1.2 ]
52+
trajectory_scale: 0.5
53+
54+
episode_len_sec: 9
55+
cost: quadratic
56+
done_on_out_of_bound: False

examples/pid/pid_experiment.py

+33
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False):
138138
system = f'quadrotor_{str(config.task_config.quad_type)}D'
139139
if config.task_config.quad_type == 4:
140140
system = 'quadrotor_2D_attitude'
141+
elif config.task_config.quad_type == 5:
142+
system = 'quadrotor_2D_attitude_5s'
141143
else:
142144
system = config.task
143145

@@ -157,6 +159,11 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False):
157159
graph1_2 = 5
158160
graph3_1 = 0
159161
graph3_2 = 2
162+
elif system == 'quadrotor_2D_attitude_5s':
163+
graph1_1 = 4
164+
graph1_2 = 5
165+
graph3_1 = 0
166+
graph3_2 = 2
160167
elif system == 'quadrotor_3D':
161168
graph1_1 = 6
162169
graph1_2 = 9
@@ -249,6 +256,32 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False):
249256
# save the plot
250257
plt.savefig(os.path.join(config.output_dir, 'pitch_action.png'))
251258

259+
if config.task_config.task == Task.TRAJ_TRACKING and system == "quadrotor_2D_attitude_5s":
260+
_, ax4 = plt.subplots()
261+
ax4.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['obs'][0][1:, 4])
262+
ax4.set_xlabel(r'time')
263+
ax4.set_ylabel(r'pitch (rad) (obs)')
264+
# ax4.set_ylim([-0.4, 0.4])
265+
plt.tight_layout()
266+
# save the plot
267+
plt.savefig(os.path.join(config.output_dir, 'pitch_obs.png'))
268+
269+
_, ax6 = plt.subplots()
270+
ax6.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['action'][0][0:, 0])
271+
ax6.set_xlabel(r'time')
272+
ax6.set_ylabel(r'Thrust (rad) (action)')
273+
plt.tight_layout()
274+
# save the plot
275+
plt.savefig(os.path.join(config.output_dir, 'thrust_action.png'))
276+
277+
_, ax7 = plt.subplots()
278+
ax7.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['action'][0][0:, 1])
279+
ax7.set_xlabel(r'time')
280+
ax7.set_ylabel(r'pitch (rad) (action)')
281+
plt.tight_layout()
282+
# save the plot
283+
plt.savefig(os.path.join(config.output_dir, 'pitch_action.png'))
284+
252285

253286
if __name__ == '__main__':
254287
run()

examples/pid/pid_experiment.sh

+1
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44

55
# SYS='quadrotor_2D'
66
SYS='quadrotor_2D_attitude'
7+
#SYS='quadrotor_2D_attitude_5s'
78
# SYS='quadrotor_3D'
89

910
# TASK='stabilization'

examples/rl/rl_experiment.py

+29-13
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,13 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'):
8484
graph3_2 = 2
8585
graph4_1 = 0
8686
graph4_2 = 1
87+
elif system == 'quadrotor_5D':
88+
graph1_1 = 4
89+
graph1_2 = 5
90+
graph3_1 = 0
91+
graph3_2 = 2
92+
graph4_1 = 0
93+
graph4_2 = 1
8794

8895
_, ax = plt.subplots()
8996
ax.plot(results['obs'][0][:, graph1_1], results['obs'][0][:, graph1_2], 'r--', label='RL Trajectory')
@@ -122,6 +129,19 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'):
122129
ax3.set_box_aspect(0.5)
123130
ax3.legend(loc='upper right')
124131

132+
if config.task == Environment.QUADROTOR and system == 'quadrotor_2D':
133+
# _, ax4 = plt.subplots()
134+
# ax4.plot(results['timestamp'][0][:], results['action'][0][:, graph4_1], 'r', label='Thrust')
135+
# ax4.set_ylabel(r'Thrust')
136+
# _, ax5 = plt.subplots()
137+
# ax5.plot(results['timestamp'][0][:], results['action'][0][:, graph4_2], 'r', label='Pitch')
138+
# ax5.set_ylabel(r'Pitch')
139+
_, ax6 = plt.subplots()
140+
ax6.plot(results['timestamp'][0][:], results['obs'][0][1:, 4], 'r', label='Thrust')
141+
ax6.set_ylabel(r'Pitch')
142+
_, ax7 = plt.subplots()
143+
ax7.plot(results['timestamp'][0][:], results['obs'][0][1:, 5], 'r', label='Pitch')
144+
ax7.set_ylabel(r'Pitch rate')
125145
if config.task == Environment.QUADROTOR and system == 'quadrotor_4D':
126146
_, ax4 = plt.subplots()
127147
ax4.plot(results['timestamp'][0][:], results['action'][0][:, graph4_1], 'r', label='Action: Thrust')
@@ -135,20 +155,16 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'):
135155
_, ax7 = plt.subplots()
136156
ax7.plot(results['timestamp'][0][:], results['obs'][0][1:, 5], 'r', label='Obs: Pitch rate')
137157
ax7.set_ylabel(r'Obs: Pitch rate')
138-
139-
if config.task == Environment.QUADROTOR and system == 'quadrotor_2D':
140-
# _, ax4 = plt.subplots()
141-
# ax4.plot(results['timestamp'][0][:], results['action'][0][:, graph4_1], 'r', label='Thrust')
142-
# ax4.set_ylabel(r'Thrust')
143-
# _, ax5 = plt.subplots()
144-
# ax5.plot(results['timestamp'][0][:], results['action'][0][:, graph4_2], 'r', label='Pitch')
145-
# ax5.set_ylabel(r'Pitch')
158+
if config.task == Environment.QUADROTOR and system == 'quadrotor_5D':
159+
_, ax4 = plt.subplots()
160+
ax4.plot(results['timestamp'][0][:], results['action'][0][:, graph4_1], 'r', label='Action: Thrust')
161+
ax4.set_ylabel(r'Action: Thrust')
162+
_, ax5 = plt.subplots()
163+
ax5.plot(results['timestamp'][0][:], results['action'][0][:, graph4_2], 'r', label='Action: Pitch')
164+
ax5.set_ylabel(r'Action: Pitch')
146165
_, ax6 = plt.subplots()
147-
ax6.plot(results['timestamp'][0][:], results['obs'][0][1:, 4], 'r', label='Thrust')
148-
ax6.set_ylabel(r'Pitch')
149-
_, ax7 = plt.subplots()
150-
ax7.plot(results['timestamp'][0][:], results['obs'][0][1:, 5], 'r', label='Pitch')
151-
ax7.set_ylabel(r'Pitch rate')
166+
ax6.plot(results['timestamp'][0][:], results['obs'][0][1:, 4], 'r', label='Obs: Pitch')
167+
ax6.set_ylabel(r'Obs: Pitch')
152168

153169
plt.tight_layout()
154170
plt.show()

examples/rl/rl_experiment.sh

+2-2
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22

33
#SYS='cartpole'
44
#SYS='quadrotor_2D'
5-
#SYS='quadrotor_2D_attitude'
6-
SYS='quadrotor_2D_attitude_5s'
5+
SYS='quadrotor_2D_attitude'
6+
#SYS='quadrotor_2D_attitude_5s'
77
#SYS='quadrotor_3D'
88

99
#TASK='stab'

examples/rl/train_rl_model.sh

+2-2
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22

33
#SYS='cartpole'
44
#SYS='quadrotor_2D'
5-
#SYS='quadrotor_2D_attitude'
6-
SYS='quadrotor_2D_attitude_5s'
5+
SYS='quadrotor_2D_attitude'
6+
#SYS='quadrotor_2D_attitude_5s'
77
#SYS='quadrotor_3D'
88

99
#TASK='stab'

safe_control_gym/envs/gym_pybullet_drones/base_aviary.py

+18
Original file line numberDiff line numberDiff line change
@@ -314,6 +314,8 @@ def _advance_simulation(self, clipped_action, disturbance_force=None):
314314
p.stepSimulation(physicsClientId=self.PYB_CLIENT)
315315
# Save the last applied action (e.g. to compute drag).
316316
self.last_clipped_action = clipped_action
317+
# if self.PHYSICS == Physics.DYN_2D:
318+
# self._set_pybullet_information()
317319
# Update and store the drones kinematic information.
318320
self._update_and_store_kinematic_information()
319321

@@ -356,6 +358,20 @@ def render(self, mode='human', close=False):
356358
format(self.ang_v[i, 0], self.ang_v[i, 1], self.ang_v[i,
357359
2]))
358360

361+
def _set_pybullet_information(self):
362+
"""Set pybullet state information from external simulation"""
363+
for i in range(self.NUM_DRONES):
364+
# Set PyBullet's state.
365+
p.resetBasePositionAndOrientation(self.DRONE_IDS[i],
366+
self.pos[i, :],
367+
p.getQuaternionFromEuler(self.rpy[i, :]),
368+
physicsClientId=self.PYB_CLIENT)
369+
# Note: the base's velocity only stored and not used #
370+
p.resetBaseVelocity(self.DRONE_IDS[i],
371+
self.vel[i, :],
372+
self.ang_v[i, :], # ang_vel not computed by DYN
373+
physicsClientId=self.PYB_CLIENT)
374+
359375
def _update_and_store_kinematic_information(self):
360376
'''Updates and stores the drones kinematic information.
361377
@@ -679,6 +695,7 @@ def _dynamics_2d(self, rpm, nth_drone):
679695
ang_v = self.ang_v[nth_drone, :]
680696
rpy_rates = self.rpy_rates[nth_drone, :]
681697
# rotation = np.array(p.getMatrixFromQuaternion(quat)).reshape(3, 3)
698+
682699
# Compute forces and torques.
683700
forces = np.array(rpm ** 2) * self.KF
684701
# Update state with discrete time dynamics.
@@ -691,6 +708,7 @@ def _dynamics_2d(self, rpm, nth_drone):
691708
X_dot = self.X_dot_fun(state, action).full()[:, 0]
692709
next_state = state + X_dot*self.PYB_TIMESTEP
693710

711+
# Updated information
694712
pos = np.array([next_state[0], 0, next_state[4]])
695713
rpy = np.array([0, next_state[7], 0])
696714
vel = np.array([next_state[1], 0, next_state[5]])

safe_control_gym/envs/gym_pybullet_drones/quadrotor.py

+8-2
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
from safe_control_gym.envs.gym_pybullet_drones.quadrotor_utils import (AttitudeControl, QuadType, cmd2pwm,
1919
pwm2rpm)
2020
from safe_control_gym.math_and_models.symbolic_systems import SymbolicModel
21-
from safe_control_gym.math_and_models.transformations import csRotXYZ, transform_trajectory
21+
from safe_control_gym.math_and_models.transformations import csRotXYZ, transform_trajectory, get_quaternion_from_euler
2222

2323

2424
class Quadrotor(BaseAviary):
@@ -596,7 +596,12 @@ def _setup_symbolic(self, prior_prop={}, **kwargs):
596596
z_dot,
597597
(18.112984649321753 * T + 3.7613154938448576) * cs.cos(theta) - g,
598598
theta_dot,
599-
-60.00143727772195 * theta + 60.00143727772195 * P)
599+
# 60 * (60 * (P - theta) - theta_dot)
600+
-143.9 * theta - 13.02 * theta_dot + 122.5 * P
601+
# 2.027 * (64.2 * P - 72.76 * theta) - 13.75 * theta_dot
602+
# -267.8 * theta - 13.41 * theta_dot + 187.5 * P
603+
# - 44.43 * theta - 10.33 * theta_dot + 32.81 * P
604+
)
600605
# Define observation.
601606
Y = cs.vertcat(x, x_dot, z, z_dot, theta, theta_dot)
602607
elif self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE_5S:
@@ -909,6 +914,7 @@ def _preprocess_control(self, action):
909914
# print(f"collective_thrust: {collective_thrust}, pitch: {pitch}")
910915

911916
_, quat = p.getBasePositionAndOrientation(self.DRONE_IDS[0], physicsClientId=self.PYB_CLIENT)
917+
# quat = get_quaternion_from_euler(self.rpy[0, :])
912918
thrust_action = self.attitude_control._dslPIDAttitudeControl(collective_thrust / 4,
913919
quat, np.array([0, pitch, 0]))
914920
# input thrust is in Newton

safe_control_gym/envs/gym_pybullet_drones/quadrotor_utils.py

+3
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55

66
import numpy as np
77
import pybullet as p
8+
from safe_control_gym.math_and_models.transformations import quaternion_rotation_matrix, euler_from_quaternion
89
from scipy.spatial.transform import Rotation
910

1011

@@ -157,6 +158,8 @@ def _dslPIDAttitudeControl(self,
157158
sim_timestep = self.sim_timestep
158159
cur_rotation = np.array(p.getMatrixFromQuaternion(cur_quat)).reshape(3, 3)
159160
cur_rpy = np.array(p.getEulerFromQuaternion(cur_quat))
161+
# cur_rotation = quaternion_rotation_matrix(cur_quat)
162+
# cur_rpy = euler_from_quaternion(cur_quat)
160163
target_quat = (Rotation.from_euler('XYZ', target_euler, degrees=False)).as_quat()
161164
w, x, y, z = target_quat
162165
target_rotation = (Rotation.from_quat([w, x, y, z])).as_matrix()

0 commit comments

Comments
 (0)