diff --git a/examples/lqr/config_overrides/quadrotor_2D_attitude/lqr_quadrotor_2D_attitude_tracking.yaml b/examples/lqr/config_overrides/quadrotor_2D_attitude/lqr_quadrotor_2D_attitude_tracking.yaml new file mode 100644 index 000000000..f28d72845 --- /dev/null +++ b/examples/lqr/config_overrides/quadrotor_2D_attitude/lqr_quadrotor_2D_attitude_tracking.yaml @@ -0,0 +1,10 @@ +algo: lqr +algo_config: + # Cost parameters + q_lqr: [1, 0.1, 1, 0.1, 0.1, 0.1] + r_lqr: [0.1] + + # Model arguments + # Note: Higher simulation frequency is required if using controller designed + # based on the continuous-time model + discrete_dynamics: True diff --git a/examples/lqr/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml b/examples/lqr/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml new file mode 100644 index 000000000..f38f9408e --- /dev/null +++ b/examples/lqr/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml @@ -0,0 +1,59 @@ +task_config: + seed: 1337 + info_in_reset: True + ctrl_freq: 60 + pyb_freq: 1200 + physics: pyb + quad_type: 4 + + init_state: + init_x: 0 + init_x_dot: 0 + init_z: 1.15 + init_z_dot: 0 + init_theta: 0 + init_theta_dot: 0 + randomized_init: True + randomized_inertial_prop: False + + init_state_randomization_info: + init_x: + distrib: 'uniform' + low: -0.01 + high: 0.01 + init_x_dot: + distrib: 'uniform' + low: -0.01 + high: 0.01 + init_z: + distrib: 'uniform' + low: -0.01 + high: 0.01 + init_z_dot: + distrib: 'uniform' + low: -0.01 + high: 0.01 + init_theta: + distrib: 'uniform' + low: -0.02 + high: 0.02 + init_theta_dot: + distrib: 'uniform' + low: -0.02 + high: 0.02 + + task: traj_tracking + task_info: + trajectory_type: figure8 + num_cycles: 1 + trajectory_plane: 'xz' + trajectory_position_offset: [ 0, 1.2 ] + trajectory_scale: 0.5 + + inertial_prop: + M: 0.027 + Iyy: 1.4e-05 + + episode_len_sec: 10 + cost: rl_reward + obs_goal_horizon: 1 diff --git a/examples/lqr/lqr_experiment.py b/examples/lqr/lqr_experiment.py index 4b6b46d86..2df8a80e0 100644 --- a/examples/lqr/lqr_experiment.py +++ b/examples/lqr/lqr_experiment.py @@ -15,7 +15,7 @@ from safe_control_gym.utils.registration import make -def run(gui=True, n_episodes=1, n_steps=None, save_data=False): +def run(gui=False, n_episodes=1, n_steps=None, save_data=False): '''The main function running LQR and iLQR experiments. Args: diff --git a/examples/lqr/lqr_experiment.sh b/examples/lqr/lqr_experiment.sh index 2e870da4e..e646f17bd 100755 --- a/examples/lqr/lqr_experiment.sh +++ b/examples/lqr/lqr_experiment.sh @@ -2,12 +2,13 @@ # LQR Experiment. -SYS='cartpole' +#SYS='cartpole' # SYS='quadrotor_2D' +SYS='quadrotor_2D_attitude' # SYS='quadrotor_3D' -TASK='stabilization' -# TASK='tracking' +#TASK='stabilization' +TASK='tracking' ALGO='lqr' # ALGO='ilqr' diff --git a/examples/pid/config_overrides/quadrotor_2D/quadrotor_2D_tracking.yaml b/examples/pid/config_overrides/quadrotor_2D/quadrotor_2D_tracking.yaml index 8520e64eb..e29d21f42 100644 --- a/examples/pid/config_overrides/quadrotor_2D/quadrotor_2D_tracking.yaml +++ b/examples/pid/config_overrides/quadrotor_2D/quadrotor_2D_tracking.yaml @@ -2,47 +2,55 @@ task_config: seed: 1337 info_in_reset: True ctrl_freq: 60 - pyb_freq: 840 + pyb_freq: 1200 gui: False - physics: pyb + physics: dyn_2d quad_type: 2 + init_state: + init_x: 0 + init_x_dot: 0 + init_z: 1.15 + init_z_dot: 0 + init_theta: 0 + init_theta_dot: 0 + randomized_init: False + randomized_inertial_prop: False + init_state_randomization_info: init_x: distrib: 'uniform' - low: -1 - high: 1 + low: -0.01 + high: 0.01 init_x_dot: distrib: 'uniform' - low: -0.1 - high: 0.1 + low: -0.01 + high: 0.01 init_z: distrib: 'uniform' - low: 0.5 - high: 1.5 + low: -0.01 + high: 0.01 init_z_dot: distrib: 'uniform' - low: -0.1 - high: 0.1 + low: -0.01 + high: 0.01 init_theta: distrib: 'uniform' - low: -0.2 - high: 0.2 + low: -0.02 + high: 0.02 init_theta_dot: distrib: 'uniform' - low: -0.1 - high: 0.1 - randomized_init: True - randomized_inertial_prop: False + low: -0.02 + high: 0.02 task: traj_tracking task_info: trajectory_type: figure8 num_cycles: 1 trajectory_plane: 'xz' - trajectory_position_offset: [0, 1] + trajectory_position_offset: [ 0, 1.2 ] trajectory_scale: 0.5 - episode_len_sec: 9 + episode_len_sec: 10 cost: quadratic - done_on_out_of_bound: True + done_on_out_of_bound: False diff --git a/examples/pid/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml b/examples/pid/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml index 8834ab323..c23f844c2 100644 --- a/examples/pid/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml +++ b/examples/pid/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_tracking.yaml @@ -1,44 +1,56 @@ task_config: seed: 1337 info_in_reset: True - ctrl_freq: 60 - pyb_freq: 840 + ctrl_freq: 50 + pyb_freq: 1000 gui: False physics: pyb quad_type: 4 + init_state: + init_x: 0 + init_x_dot: 0 + init_z: 1.15 + init_z_dot: 0 + init_theta: 0 + init_theta_dot: 0 + randomized_init: True + randomized_inertial_prop: False + init_state_randomization_info: init_x: distrib: 'uniform' - low: -1 - high: 1 + low: -0.01 + high: 0.01 init_x_dot: distrib: 'uniform' - low: -0.1 - high: 0.1 + low: -0.01 + high: 0.01 init_z: distrib: 'uniform' - low: 0.5 - high: 1.5 + low: -0.01 + high: 0.01 init_z_dot: distrib: 'uniform' - low: -0.1 - high: 0.1 + low: -0.01 + high: 0.01 init_theta: distrib: 'uniform' - low: -0.2 - high: 0.2 - randomized_init: True - randomized_inertial_prop: False + low: -0.02 + high: 0.02 + init_theta_dot: + distrib: 'uniform' + low: -0.02 + high: 0.02 task: traj_tracking task_info: trajectory_type: figure8 num_cycles: 1 trajectory_plane: 'xz' - trajectory_position_offset: [0, 1] + trajectory_position_offset: [ 0, 1.2 ] trajectory_scale: 0.5 episode_len_sec: 9 cost: quadratic - done_on_out_of_bound: True + done_on_out_of_bound: False diff --git a/examples/pid/pid_experiment.py b/examples/pid/pid_experiment.py index ed5dee36a..53b574f62 100644 --- a/examples/pid/pid_experiment.py +++ b/examples/pid/pid_experiment.py @@ -1,4 +1,4 @@ -'''A PID example on a quadrotor.''' +"""A PID example on a quadrotor.""" import os import pickle @@ -16,14 +16,14 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): - '''The main function running PID experiments. + """The main function running PID experiments. Args: gui (bool): Whether to display the gui and plot graphs. n_episodes (int): The number of episodes to execute. n_steps (int): The total number of steps to execute. save_data (bool): Whether to save the collected experiment data. - ''' + """ # Create the configuration dictionary. CONFIG_FACTORY = ConfigFactory() @@ -51,7 +51,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): if custom_trajectory: # Set iterations and episode counter. - ITERATIONS = int(config.task_config['episode_len_sec'] * config.task_config['ctrl_freq']) + 2 # +2 for start and end of reference + ITERATIONS = int(config.task_config['episode_len_sec'] * config.task_config[ + 'ctrl_freq']) + 2 # +2 for start and end of reference # Curve fitting with waypoints. waypoints = np.array([(0, 0, 0), (0.2, 0.5, 0.5), (0.5, 0.1, 0.6), (1, 1, 1), (1.3, 1, 1.2)]) @@ -80,7 +81,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): if config.task_config.task == 'traj_tracking' and gui is True: if config.task_config.quad_type == 2: - ref_3D = np.hstack([ctrl.env.X_GOAL[:, [0]], np.zeros(ctrl.env.X_GOAL[:, [0]].shape), ctrl.env.X_GOAL[:, [2]]]) + ref_3D = np.hstack( + [ctrl.env.X_GOAL[:, [0]], np.zeros(ctrl.env.X_GOAL[:, [0]].shape), ctrl.env.X_GOAL[:, [2]]]) else: ref_3D = ctrl.env.X_GOAL[:, [0, 2, 4]] # Plot in 3D. @@ -115,25 +117,27 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): with open(f'./temp-data/{config.algo}_data_{config.task_config.task}.pkl', 'wb') as file: pickle.dump(results, file) - iterations = len(trajs_data['action'][0]) - for i in range(iterations): - # Step the environment and print all returned information. - obs, reward, done, info, action = trajs_data['obs'][0][i], trajs_data['reward'][0][i], trajs_data['done'][0][i], trajs_data['info'][0][i], trajs_data['action'][0][i] - - # # Print the last action and the information returned at each step. - # print(i, '-th step.') - # print(action, '\n', obs, '\n', reward, '\n', done, '\n', info, '\n') + # iterations = len(trajs_data['action'][0]) + # for i in range(iterations): + # # Step the environment and print all returned information. + # obs, reward, done, info, action = trajs_data['obs'][0][i], trajs_data['reward'][0][i], + # trajs_data['done'][0][i], trajs_data['info'][0][i], trajs_data['action'][0][i] + # + # # # Print the last action and the information returned at each step. + # # print(i, '-th step.') + # # print(action, '\n', obs, '\n', reward, '\n', done, '\n', info, '\n') elapsed_sec = trajs_data['timestamp'][0][-1] - trajs_data['timestamp'][0][0] - # print(f'\n{iterations} iterations (@{config.task_config.ctrl_freq}Hz) in {elapsed_sec:.2f} seconds, i.e. {iterations / elapsed_sec:.2f} steps/sec for a {(iterations * (1. / config.task_config.ctrl_freq)) / elapsed_sec:.2f}x speedup.\n') - + # print(f'\n{iterations} iterations (@{config.task_config.ctrl_freq}Hz) in {elapsed_sec:.2f} seconds, + # i.e. {iterations / elapsed_sec:.2f} steps/sec for a + # {(iterations * (1. / config.task_config.ctrl_freq)) / elapsed_sec:.2f}x speedup.\n') # print('FINAL METRICS - ' + ', '.join([f'{key}: {value}' for key, value in metrics.items()])) set_dir_from_config(config) if config.task == Environment.QUADROTOR: system = f'quadrotor_{str(config.task_config.quad_type)}D' if config.task_config.quad_type == 4: - system = 'quadrotor_2D' + system = 'quadrotor_2D_attitude' else: system = config.task @@ -148,6 +152,11 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): graph1_2 = 5 graph3_1 = 0 graph3_2 = 2 + elif system == 'quadrotor_2D_attitude': + graph1_1 = 4 + graph1_2 = 5 + graph3_1 = 0 + graph3_2 = 2 elif system == 'quadrotor_3D': graph1_1 = 6 graph1_2 = 9 @@ -156,7 +165,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): _, ax = plt.subplots() # ax.plot(trajs_data['obs'][0][:, graph1_1], trajs_data['obs'][0][:, graph1_2], 'r--', label='Agent Trajectory') - # ax.scatter(trajs_data['obs'][0][0, graph1_1], trajs_data['obs'][0][0, graph1_2], color='g', marker='o', s=100, label='Initial State') + # ax.scatter(trajs_data['obs'][0][0, graph1_1], trajs_data['obs'][0][0, graph1_2], + # color='g', marker='o', s=100, label='Initial State') # ax.set_xlabel(r'$\theta$') # ax.set_ylabel(r'$\dot{\theta}$') # ax.set_box_aspect(0.5) @@ -166,7 +176,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): # if config.task_config.task == Task.TRAJ_TRACKING and config.task == Environment.CARTPOLE: # _, ax2 = plt.subplots() - # ax2.plot(np.linspace(0, 20, trajs_data['obs'][0].shape[0]), trajs_data['obs'][0][:, 0], 'r--', label='Agent Trajectory') + # ax2.plot(np.linspace(0, 20, trajs_data['obs'][0].shape[0]), trajs_data['obs'][0][:, 0], + # 'r--', label='Agent Trajectory') # ax2.plot(np.linspace(0, 20, trajs_data['obs'][0].shape[0]), ctrl.env.X_GOAL[:, 0], 'b', label='Reference') # ax2.set_xlabel(r'Time') # ax2.set_ylabel(r'X') @@ -176,7 +187,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): # plt.savefig(os.path.join(config.output_dir, 'trajectory_time_x.png')) # elif config.task == Environment.QUADROTOR: # _, ax2 = plt.subplots() - # ax2.plot(trajs_data['obs'][0][:, graph3_1 + 1], trajs_data['obs'][0][:, graph3_2 + 1], 'r--', label='Agent Trajectory') + # ax2.plot(trajs_data['obs'][0][:, graph3_1 + 1], trajs_data['obs'][0][:, graph3_2 + 1], + # 'r--', label='Agent Trajectory') # ax2.set_xlabel(r'x_dot') # ax2.set_ylabel(r'z_dot') # ax2.set_box_aspect(0.5) @@ -188,7 +200,8 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): ax3.plot(trajs_data['obs'][0][:, graph3_1], trajs_data['obs'][0][:, graph3_2], 'r--', label='Agent Trajectory') if config.task_config.task == Task.TRAJ_TRACKING and config.task == Environment.QUADROTOR: ax3.plot(ctrl.env.X_GOAL[:, graph3_1], ctrl.env.X_GOAL[:, graph3_2], 'g--', label='Reference') - ax3.scatter(trajs_data['obs'][0][0, graph3_1], trajs_data['obs'][0][0, graph3_2], color='g', marker='o', s=100, label='Initial State') + ax3.scatter(trajs_data['obs'][0][0, graph3_1], trajs_data['obs'][0][0, graph3_2], color='g', marker='o', s=100, + label='Initial State') ax3.set_xlabel(r'X') if config.task == Environment.CARTPOLE: ax3.set_ylabel(r'Vel') @@ -201,6 +214,41 @@ def run(gui=False, n_episodes=1, n_steps=None, save_data=False): # save the plot plt.savefig(os.path.join(config.output_dir, 'trajectory_x.png')) + if config.task_config.task == Task.TRAJ_TRACKING and system == "quadrotor_2D" or system == "quadrotor_2D_attitude": + _, ax4 = plt.subplots() + ax4.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['obs'][0][1:, 4]) + ax4.set_xlabel(r'time') + ax4.set_ylabel(r'pitch (rad) (obs)') + # ax4.set_ylim([-0.4, 0.4]) + plt.tight_layout() + # save the plot + plt.savefig(os.path.join(config.output_dir, 'pitch_obs.png')) + + _, ax5 = plt.subplots() + ax5.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['obs'][0][1:, 5]) + # ax5.plot(trajs_data['timestamp'][0][1:], np.diff(trajs_data['obs'][0][1:, 4])*120) + ax5.set_xlabel(r'time') + ax5.set_ylabel(r'pitch rate (rad/s) (obs)') + plt.tight_layout() + # save the plot + plt.savefig(os.path.join(config.output_dir, 'pitch_rate_obs.png')) + + _, ax6 = plt.subplots() + ax6.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['action'][0][0:, 0]) + ax6.set_xlabel(r'time') + ax6.set_ylabel(r'Thrust (rad) (action)') + plt.tight_layout() + # save the plot + plt.savefig(os.path.join(config.output_dir, 'thrust_action.png')) + + _, ax7 = plt.subplots() + ax7.plot(trajs_data['timestamp'][0][0:] - trajs_data['timestamp'][0][0], trajs_data['action'][0][0:, 1]) + ax7.set_xlabel(r'time') + ax7.set_ylabel(r'pitch (rad) (action)') + plt.tight_layout() + # save the plot + plt.savefig(os.path.join(config.output_dir, 'pitch_action.png')) + if __name__ == '__main__': run() diff --git a/examples/pid/pid_experiment.sh b/examples/pid/pid_experiment.sh index 79ab89112..d2204629d 100755 --- a/examples/pid/pid_experiment.sh +++ b/examples/pid/pid_experiment.sh @@ -3,15 +3,16 @@ # PID Experiment. # SYS='quadrotor_2D' -SYS='quadrotor_3D' +SYS='quadrotor_2D_attitude' +# SYS='quadrotor_3D' # TASK='stabilization' TASK='tracking' -# TRAJ_TYPE='figure8' + TRAJ_TYPE='figure8' # TRAJ_TYPE='circle' # TRAJ_TYPE='square' -TRAJ_TYPE='custom' +#TRAJ_TYPE='custom' python3 ./pid_experiment.py \ --task quadrotor \ diff --git a/examples/rl/config_overrides/quadrotor_2D_attitude/ppo_quadrotor_2D_attitude.yaml b/examples/rl/config_overrides/quadrotor_2D_attitude/ppo_quadrotor_2D_attitude.yaml index 45a1232e1..460daf3fb 100644 --- a/examples/rl/config_overrides/quadrotor_2D_attitude/ppo_quadrotor_2D_attitude.yaml +++ b/examples/rl/config_overrides/quadrotor_2D_attitude/ppo_quadrotor_2D_attitude.yaml @@ -1,4 +1,3 @@ -algo: ppo algo_config: # model args hidden_dim: 128 @@ -15,14 +14,15 @@ algo_config: critic_lr: 0.001 # runner args - max_env_steps: 200000 + max_env_steps: 480000 rollout_batch_size: 4 rollout_steps: 1000 + eval_batch_size: 50 # misc - log_interval: 2000 + log_interval: 8000 save_interval: 0 num_checkpoints: 0 - eval_interval: 2000 + eval_interval: 8000 eval_save_best: True tensorboard: False diff --git a/examples/rl/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_track.yaml b/examples/rl/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_track.yaml index 37471f4fc..524db0880 100644 --- a/examples/rl/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_track.yaml +++ b/examples/rl/config_overrides/quadrotor_2D_attitude/quadrotor_2D_attitude_track.yaml @@ -2,10 +2,10 @@ task_config: seed: 1337 info_in_reset: True ctrl_freq: 60 - pyb_freq: 60 + pyb_freq: 1200 physics: pyb quad_type: 4 - normalized_rl_action_space: False + normalized_rl_action_space: True init_state: init_x: 0 @@ -60,18 +60,19 @@ task_config: obs_goal_horizon: 1 # RL Reward - rew_state_weight: [1.0, 0.1, 1.0, 0.1, 1.0, 1.0] - rew_act_weight: 1.0 + rew_state_weight: [1.0, 0.01, 1.0, 0.01, 0.1, 0.5] + rew_act_weight: 0.1 rew_exponential: True - constraints: - - constraint_form: default_constraint - constrained_variable: state - upper_bounds: [2, 1, 2, 1, 0.2, 2.5] - lower_bounds: [-2, -1, 0, -1, -0.2, -2.5] - - constraint_form: default_constraint - constrained_variable: input - upper_bounds: [0.58, 0.8] - lower_bounds: [0.06, -0.8] - done_on_out_of_bound: False +# constraints: +# - constraint_form: default_constraint +# constrained_variable: state +# upper_bounds: [2, 1, 2, 1, 0.2, 2.5] +# lower_bounds: [-2, -1, 0, -1, -0.2, -2.5] +# - constraint_form: default_constraint +# constrained_variable: input +# upper_bounds: [0.58, 0.8] +# lower_bounds: [0.06, -0.8] + + done_on_out_of_bound: True done_on_violation: False diff --git a/examples/rl/config_overrides/quadrotor_2D_attitude/sac_quadrotor_2D_attitude.yaml b/examples/rl/config_overrides/quadrotor_2D_attitude/sac_quadrotor_2D_attitude.yaml index 4ffe06ced..2e7f2db4e 100644 --- a/examples/rl/config_overrides/quadrotor_2D_attitude/sac_quadrotor_2D_attitude.yaml +++ b/examples/rl/config_overrides/quadrotor_2D_attitude/sac_quadrotor_2D_attitude.yaml @@ -2,7 +2,7 @@ algo_config: # model args hidden_dim: 128 activation: "relu" - use_entropy_tuning: False + use_entropy_tuning: True # optim args train_interval: 100 @@ -12,18 +12,18 @@ algo_config: entropy_lr: 0.001 # runner args - max_env_steps: 50000 + max_env_steps: 200000 warm_up_steps: 1000 rollout_batch_size: 4 num_workers: 1 max_buffer_size: 50000 - deque_size: 10 - eval_batch_size: 10 + deque_size: 50 + eval_batch_size: 50 # misc - log_interval: 1000 + log_interval: 4000 save_interval: 0 num_checkpoints: 0 - eval_interval: 1000 + eval_interval: 4000 eval_save_best: True tensorboard: False diff --git a/examples/rl/config_overrides/quadrotor_2D_attitude/td3_quadrotor_2D_attitude.yaml b/examples/rl/config_overrides/quadrotor_2D_attitude/td3_quadrotor_2D_attitude.yaml index 19240207c..b968a24ca 100644 --- a/examples/rl/config_overrides/quadrotor_2D_attitude/td3_quadrotor_2D_attitude.yaml +++ b/examples/rl/config_overrides/quadrotor_2D_attitude/td3_quadrotor_2D_attitude.yaml @@ -12,13 +12,13 @@ algo_config: critic_lr: 0.001 # runner args - max_env_steps: 100000 + max_env_steps: 200000 warm_up_steps: 1000 rollout_batch_size: 4 num_workers: 1 - max_buffer_size: 100000 + max_buffer_size: 50000 deque_size: 10 - eval_batch_size: 10 + eval_batch_size: 50 # misc log_interval: 2000 diff --git a/examples/rl/data_analysis.ipynb b/examples/rl/data_analysis.ipynb index a82941cbe..7be65d6e6 100644 --- a/examples/rl/data_analysis.ipynb +++ b/examples/rl/data_analysis.ipynb @@ -22,7 +22,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 13, "metadata": {}, "outputs": [], "source": [ @@ -32,12 +32,16 @@ " \"sac\": os.getcwd()+\"/Results/cartpole_sac_data/\", \n", " \"td3\": os.getcwd()+\"/Results/cartpole_td3_data/\", \n", " \"ddpg\": os.getcwd()+\"/Results/cartpole_ddpg_data/\"}\n", - "seeds = [i for i in range(0,10)]\n" + "#data_paths = {\"ppo\": os.getcwd()+\"/Results/Olaf/quadrotor_2D_ppo_data/\", \n", + "# \"sac\": os.getcwd()+\"/Results/Olaf/quadrotor_2D_sac_data/\", \n", + "# \"td3\": os.getcwd()+\"/Results/Olaf/quadrotor_2D_td3_data/\"}\n", + "seeds = [i for i in range(0,10)]\n", + "#seeds = [0]" ] }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 14, "metadata": {}, "outputs": [], "source": [ @@ -63,7 +67,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 15, "metadata": {}, "outputs": [ { @@ -92,7 +96,7 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 16, "metadata": {}, "outputs": [ { @@ -642,7 +646,7 @@ " 0. , 1.8, 11.2, 0. , 0. , 0. , 0. , 0. , 0. ])}}}" ] }, - "execution_count": 5, + "execution_count": 16, "metadata": {}, "output_type": "execute_result" } @@ -653,7 +657,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 19, "metadata": {}, "outputs": [ { @@ -712,13 +716,13 @@ "Text(0.5, 1.0, 'Task: Cartpole')" ] }, - "execution_count": 8, + "execution_count": 19, "metadata": {}, "output_type": "execute_result" }, { "data": { - "image/png": "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", + "image/png": "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", "text/plain": [ "
" ] @@ -770,10 +774,10 @@ "\n", "\n", "plt.legend()\n", - "plt.ylim(-200,0)\n", + "plt.ylim(-200,00)\n", "plt.xscale(\"log\")\n", "plt.xlabel(\"Training steps\")\n", - "plt.ylabel(\"% Constraint violation\")\n", + "plt.ylabel(\"Performance\")\n", "plt.title(\"Task: Cartpole\")\n", "# plt.savefig(\"perf1.pdf\",bbox_inches=\"tight\", pad_inches=0.0)" ] diff --git a/examples/rl/models/ppo/model_best.pt b/examples/rl/models/ppo/model_best.pt new file mode 100644 index 000000000..7ec2ac3c7 Binary files /dev/null and b/examples/rl/models/ppo/model_best.pt differ diff --git a/examples/rl/models/sac/model_best.pt b/examples/rl/models/sac/model_best.pt new file mode 100644 index 000000000..3a39a900e Binary files /dev/null and b/examples/rl/models/sac/model_best.pt differ diff --git a/examples/rl/models/td3/model_best.pt b/examples/rl/models/td3/model_best.pt index f91892982..0bdcacd39 100644 Binary files a/examples/rl/models/td3/model_best.pt and b/examples/rl/models/td3/model_best.pt differ diff --git a/examples/rl/rl_experiment.py b/examples/rl/rl_experiment.py index 96fc7a411..dc08aa849 100644 --- a/examples/rl/rl_experiment.py +++ b/examples/rl/rl_experiment.py @@ -130,10 +130,10 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'): ax5.plot(results['timestamp'][0][:], results['action'][0][:, graph4_2], 'r', label='Pitch') ax5.set_ylabel(r'Pitch') _, ax6 = plt.subplots() - ax6.plot(results['timestamp'][0][:], results['obs'][0][1:, 5], 'r', label='Thrust') + ax6.plot(results['timestamp'][0][:], results['obs'][0][1:, 4], 'r', label='Thrust') ax6.set_ylabel(r'Pitch') _, ax7 = plt.subplots() - ax7.plot(results['timestamp'][0][:], results['obs'][0][1:, 6], 'r', label='Pitch') + ax7.plot(results['timestamp'][0][:], results['obs'][0][1:, 5], 'r', label='Pitch') ax7.set_ylabel(r'Pitch rate') if config.task == Environment.QUADROTOR and system == 'quadrotor_2D': diff --git a/examples/rl/rl_experiment.sh b/examples/rl/rl_experiment.sh index b72fae59e..cb137d74a 100755 --- a/examples/rl/rl_experiment.sh +++ b/examples/rl/rl_experiment.sh @@ -1,16 +1,16 @@ #!/bin/bash #SYS='cartpole' -SYS='quadrotor_2D' -#SYS='quadrotor_2D_attitude' +#SYS='quadrotor_2D' +SYS='quadrotor_2D_attitude' #SYS='quadrotor_3D' #TASK='stab' TASK='track' #ALGO='ppo' -#ALGO='sac' -ALGO='td3' +ALGO='sac' +#ALGO='td3' #ALGO='safe_explorer_ppo' if [ "$SYS" == 'cartpole' ]; then diff --git a/examples/rl/train_rl_model.sh b/examples/rl/train_rl_model.sh index c49d8f52f..f5393ec1d 100755 --- a/examples/rl/train_rl_model.sh +++ b/examples/rl/train_rl_model.sh @@ -1,18 +1,17 @@ #!/bin/bash #SYS='cartpole' -SYS='quadrotor_2D' -#SYS='quadrotor_2D_attitude' +#SYS='quadrotor_2D' +SYS='quadrotor_2D_attitude' #SYS='quadrotor_3D' #TASK='stab' TASK='track' -#ALGO='ppo' +ALGO='ppo' #ALGO='sac' -ALGO='td3' +#ALGO='td3' #ALGO='ddpg' - #ALGO='safe_explorer_ppo' if [ "$SYS" == 'cartpole' ]; then diff --git a/safe_control_gym/controllers/pid/pid.py b/safe_control_gym/controllers/pid/pid.py index 1c928d20c..4132f1559 100644 --- a/safe_control_gym/controllers/pid/pid.py +++ b/safe_control_gym/controllers/pid/pid.py @@ -1,7 +1,7 @@ -'''PID control class for Crazyflies. +"""PID control class for Crazyflies. Based on work conducted at UTIAS' DSL by SiQi Zhou and James Xu. -''' +""" import math import os @@ -15,7 +15,7 @@ class PID(BaseController): - '''PID Class.''' + """PID Class.""" def __init__(self, env_func=None, @@ -34,7 +34,7 @@ def __init__(self, max_pwm: float = 65535, **kwargs ): - '''Common control classes __init__ method. + """Common control classes __init__ method. Args: g (float, optional): The gravitational acceleration in m/s^2. @@ -50,7 +50,7 @@ def __init__(self, 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) @@ -81,7 +81,7 @@ def __init__(self, self.reset() def select_action(self, obs, info=None): - '''Determine the action to take at the current timestep. + """Determine the action to take at the current timestep. Args: obs (ndarray): The observation at this timestep. @@ -89,7 +89,7 @@ def select_action(self, obs, info=None): Returns: action (ndarray): The action chosen by the controller. - ''' + """ step = self.extract_step(info) @@ -111,6 +111,9 @@ def select_action(self, obs, info=None): target_vel = np.array([self.reference[step, 1], 0, self.reference[step, 3]]) + + # target_pos = np.array([0.2, 0, 0.2]) + # target_vel = np.array([0, 0, 0]) elif self.env.TASK == Task.STABILIZATION: target_pos = np.array([self.reference[0], 0, self.reference[2]]) target_vel = np.array([0, 0, 0]) @@ -135,21 +138,68 @@ def select_action(self, obs, info=None): 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 + target_vel) + action = np.zeros(2) if self.env.QUAD_TYPE == 2: + rpm = self._dslPIDAttitudeControl(thrust, + cur_quat, + computed_target_rpy, + target_rpy_rates) + action = rpm + action = self.KF * action ** 2 action = np.array([action[0] + action[3], action[1] + action[2]]) elif self.env.QUAD_TYPE == 4: # 2D quadrotor with attitude control action = np.array([self.env.attitude_control.pwm2thrust(thrust / 3) * 4, computed_target_rpy[1]]) - + #### Extra checks + # rpm = self.env.before_step(action) + # self.env._update_and_store_kinematic_information() + # cur_pos = self.env.pos[0, :] + # cur_vel = self.env.vel[0, :] + # rpy = self.env.rpy[0, :] + # rpy_rates = self.env.rpy_rates[0, :] + # ang_v = self.env.ang_v[0, :] + # cur_quat = np.array(p.getQuaternionFromEuler(rpy)) + # + # step = 1 + # for _ in range(step*20): + # # Compute forces and torques. + # forces = np.array(rpm ** 2) * self.env.KF + # # Update state with discrete time dynamics. + # state = np.hstack([cur_pos[0], cur_vel[0], cur_pos[1], cur_vel[1], cur_pos[2], cur_vel[2], + # rpy[0], rpy[1], rpy[2], ang_v[0], ang_v[1], ang_v[2]]) + # action2 = np.array([forces[0], forces[1], forces[2], forces[3]]) + # + # # update state with RK4 + # # next_state = self.fd_func(x0=state, p=input)['xf'].full()[:, 0] + # X_dot = self.env.X_dot_fun(state, action2).full()[:, 0] + # next_state = state + X_dot * self.env.PYB_TIMESTEP/step + # + # cur_pos = np.array([next_state[0], 0, next_state[4]]) + # cur_vel = np.array([next_state[1], 0, next_state[5]]) + # rpy = np.array([0, next_state[7], 0]) + # rpy_rates = X_dot[6:9] + # ang_v = np.array([0, next_state[10], 0]) + # cur_quat = np.array(p.getQuaternionFromEuler(rpy)) + # + # # attitude controller running at a higher freq + # # 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) + # # action3 = rpm + # # action3 = self.KF * action3 ** 2 + # # if self.env.QUAD_TYPE == 2: + # # action4 = np.array([action3[0] + action3[3], action3[1] + action3[2]]) + # # elif self.env.QUAD_TYPE == 4: # 2D quadrotor with attitude control + # # action4 = np.array([self.env.attitude_control.pwm2thrust(thrust / 3) * 4, computed_target_rpy[1]]) + # # rpm = self.env.before_step(action4) + # print(rpy) return action def _dslPIDPositionControl(self, @@ -160,7 +210,7 @@ def _dslPIDPositionControl(self, target_rpy, target_vel ): - '''DSL's CF2.x PID position control. + """DSL's CF2.x PID position control. Args: cur_pos (ndarray): (3,1)-shaped array of floats containing the current position. @@ -174,7 +224,7 @@ def _dslPIDPositionControl(self, 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 @@ -199,7 +249,8 @@ def _dslPIDPositionControl(self, 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]') + raise ValueError('\n[ERROR] ctrl it', self.control_counter, 'in Control._dslPIDPositionControl(), ' + 'values outside range [-pi,pi]') return thrust, target_euler, pos_e @@ -209,7 +260,7 @@ def _dslPIDAttitudeControl(self, target_euler, target_rpy_rates ): - '''DSL's CF2.x PID attitude control. + """DSL's CF2.x PID attitude control. Args: thrust (float): The target thrust along the drone z-axis. @@ -219,7 +270,7 @@ def _dslPIDAttitudeControl(self, 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)) @@ -245,22 +296,22 @@ def _dslPIDAttitudeControl(self, return self.PWM2RPM_SCALE * pwm + self.PWM2RPM_CONST def reset(self): - '''Resets the control classes. The previous step's and integral + """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. + """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) @@ -268,23 +319,23 @@ def reset_before_run(self, obs=None, info=None, env=None): self.setup_results_dict() def close(self): - '''Shuts down and cleans up lingering resources.''' + """Shuts down and cleans up lingering resources.""" self.env.close() def save(self, path): - '''Saves integral errors to checkpoint 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. + """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) diff --git a/safe_control_gym/controllers/ppo/ppo.py b/safe_control_gym/controllers/ppo/ppo.py index 98578cbbe..990c41918 100644 --- a/safe_control_gym/controllers/ppo/ppo.py +++ b/safe_control_gym/controllers/ppo/ppo.py @@ -1,4 +1,4 @@ -'''Proximal Policy Optimization (PPO) +"""Proximal Policy Optimization (PPO) Based on: * https://github.com/openai/spinningup/blob/master/spinup/algos/pytorch/ppo/ppo.py @@ -10,7 +10,7 @@ * pytorch-a2c-ppo-acktr-gail - https://github.com/ikostrikov/pytorch-a2c-ppo-acktr-gail * openai spinning up - ppo - https://github.com/openai/spinningup/tree/master/spinup/algos/pytorch/ppo * stable baselines3 - ppo - https://github.com/DLR-RM/stable-baselines3/tree/master/stable_baselines3/ppo -''' +""" import os import time @@ -30,7 +30,7 @@ class PPO(BaseController): - '''Proximal policy optimization.''' + """Proximal policy optimization.""" def __init__(self, env_func, @@ -85,7 +85,7 @@ def __init__(self, self.logger = ExperimentLogger(output_dir, log_file_out=log_file_out, use_tensorboard=use_tensorboard) def reset(self): - '''Do initializations for training or evaluation.''' + """Do initializations for training or evaluation.""" if self.training: # set up stats tracking self.env.add_tracker('constraint_violation', 0) @@ -103,7 +103,7 @@ def reset(self): self.env.add_tracker('mse', 0, mode='queue') def close(self): - '''Shuts down and cleans up lingering resources.''' + """Shuts down and cleans up lingering resources.""" self.env.close() if self.training: self.eval_env.close() @@ -112,7 +112,7 @@ def close(self): def save(self, path ): - '''Saves model params and experiment state to checkpoint path.''' + """Saves model params and experiment state to checkpoint path.""" path_dir = os.path.dirname(path) os.makedirs(path_dir, exist_ok=True) state_dict = { @@ -133,7 +133,7 @@ def save(self, def load(self, path ): - '''Restores model and experiment given checkpoint path.''' + """Restores model and experiment given checkpoint path.""" state = torch.load(path) # Restore policy. self.agent.load_state_dict(state['agent']) @@ -151,7 +151,7 @@ def learn(self, env=None, **kwargs ): - '''Performs learning (pre-training, training, fine-tuning, etc).''' + """Performs learning (pre-training, training, fine-tuning, etc.).""" if self.num_checkpoints > 0: step_interval = np.linspace(0, self.max_env_steps, self.num_checkpoints) @@ -191,7 +191,7 @@ def learn(self, self.log_step(results) def select_action(self, obs, info=None): - '''Determine the action to take at the current timestep. + """Determine the action to take at the current timestep. Args: obs (ndarray): The observation at this timestep. @@ -199,12 +199,11 @@ def select_action(self, obs, info=None): Returns: action (ndarray): The action chosen by the controller. - ''' + """ with torch.no_grad(): obs = torch.FloatTensor(obs).to(self.device) action = self.agent.ac.act(obs) - return action def run(self, @@ -213,7 +212,7 @@ def run(self, n_episodes=50, verbose=False, ): - '''Runs evaluation with current policy.''' + """Runs evaluation with current policy.""" self.agent.eval() self.obs_normalizer.set_read_only() if env is None: @@ -257,7 +256,7 @@ def run(self, return eval_results def train_step(self): - '''Performs a training/fine-tuning step.''' + """Performs a training/fine-tuning step.""" self.agent.train() self.obs_normalizer.unset_read_only() rollouts = PPOBuffer(self.env.observation_space, self.env.action_space, self.rollout_steps, self.rollout_batch_size) @@ -305,7 +304,7 @@ def train_step(self): def log_step(self, results ): - '''Does logging after a training step.''' + """Does logging after a training step.""" step = results['step'] # runner stats self.logger.add_scalars( diff --git a/safe_control_gym/controllers/ppo/ppo_utils.py b/safe_control_gym/controllers/ppo/ppo_utils.py index 6ddda5b70..2b1363b3b 100644 --- a/safe_control_gym/controllers/ppo/ppo_utils.py +++ b/safe_control_gym/controllers/ppo/ppo_utils.py @@ -244,7 +244,7 @@ class PPOBuffer(object): Attributes: max_length (int): maximum length of episode. batch_size (int): number of episodes per batch. - scheme (dict): describs shape & other info of data to be stored. + scheme (dict): describes shape & other info of data to be stored. keys (list): names of all data from scheme. ''' diff --git a/safe_control_gym/controllers/td3/td3_utils.py b/safe_control_gym/controllers/td3/td3_utils.py index 0b1cc9343..f78b153b7 100644 --- a/safe_control_gym/controllers/td3/td3_utils.py +++ b/safe_control_gym/controllers/td3/td3_utils.py @@ -34,6 +34,9 @@ def __init__(self, # params self.obs_space = obs_space self.act_space = act_space + low, high = act_space.low, act_space.high + self.action_space_low = torch.FloatTensor(low) + self.action_space_high = torch.FloatTensor(high) self.gamma = gamma self.eps = eps @@ -100,7 +103,7 @@ def compute_q_loss(self, batch): with torch.no_grad(): next_act = self.ac.actor(next_obs) noise = (0.5*torch.randn_like(next_act)).clamp(-0.2, 0.2) - next_act = (next_act+noise).clamp(self.act_space.low, self.act_space.high) + next_act = (next_act+noise).clamp(self.action_space_low, self.action_space_high) next_q1_targ = self.ac_targ.q1(next_obs, next_act) next_q2_targ = self.ac_targ.q2(next_obs, next_act) next_q_targ = torch.min(next_q1_targ, next_q2_targ) diff --git a/safe_control_gym/envs/benchmark_env.py b/safe_control_gym/envs/benchmark_env.py index 1a0ad8c54..16272f604 100644 --- a/safe_control_gym/envs/benchmark_env.py +++ b/safe_control_gym/envs/benchmark_env.py @@ -440,8 +440,8 @@ def before_step(self, action): self.current_raw_action = action # Pre-process/clip the action - processed_action = self._preprocess_control(action) - return processed_action + # processed_action = self._preprocess_control(action) + return action def extend_obs(self, obs, next_step): """Extends an observation with the next self.obs_goal_horizon reference points. diff --git a/safe_control_gym/envs/env_wrappers/record_episode_statistics.py b/safe_control_gym/envs/env_wrappers/record_episode_statistics.py index e2300dbae..54be70e10 100644 --- a/safe_control_gym/envs/env_wrappers/record_episode_statistics.py +++ b/safe_control_gym/envs/env_wrappers/record_episode_statistics.py @@ -1,4 +1,4 @@ -'''Record Episode Statistics.''' +"""Record Episode Statistics.""" import time from collections import deque @@ -11,10 +11,10 @@ class RecordEpisodeStatistics(gym.Wrapper): - '''Keep track of episode length and returns per instantiated env + """Keep track of episode length and returns per instantiated env Based on OpenAI's Gym wrapper record_episode_statistics.py - ''' + """ def __init__(self, env, @@ -38,12 +38,12 @@ def add_tracker(self, init_value, mode='accumulate' ): - '''Adds a specific stat to be tracked (accumulate|queue). + """Adds a specific stat to be tracked (accumulate|queue). Modes to track stats * accumulate: rolling sum, e.g. total # of constraint violations during training. * queue: finite, individual storage, e.g. returns, lengths, constraint costs. - ''' + """ self.episode_stats[name] = init_value if mode == 'accumulate': self.accumulated_stats[name] = init_value @@ -90,10 +90,10 @@ def step(self, class VecRecordEpisodeStatistics(VecEnvWrapper): - '''A vectorized wrapper that records episodic statistics. + """A vectorized wrapper that records episodic statistics. E.g. episode lengths, returns, constraint violations. - ''' + """ def __init__(self, venv, @@ -116,7 +116,7 @@ def add_tracker(self, init_value, mode='accumulate' ): - '''Adds a specific stat to be tracked (accumulated).''' + """Adds a specific stat to be tracked (accumulated).""" self.episode_stats[name] = [init_value for _ in range(self.num_envs)] if mode == 'accumulate': self.accumulated_stats[name] = init_value diff --git a/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py b/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py index bac1fa521..89c8718ad 100644 --- a/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py +++ b/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py @@ -17,8 +17,10 @@ import numpy as np import pybullet as p import pybullet_data +import casadi as cs from safe_control_gym.envs.benchmark_env import BenchmarkEnv +from safe_control_gym.math_and_models.transformations import csRotXYZ egl = pkgutil.get_loader('eglRenderer') @@ -38,6 +40,8 @@ class Physics(str, Enum): PYB_DRAG = 'pyb_drag' # PyBullet physics update with drag. PYB_DW = 'pyb_dw' # PyBullet physics update with downwash. PYB_GND_DRAG_DW = 'pyb_gnd_drag_dw' # PyBullet physics update with ground effect, drag, and downwash. + RK4 = 'rk4' # Update with a Runge-Kutta 4th order integrator. + DYN_2D = 'dyn_2d' # Update with SysId 5 state dynamics model class ImageType(int, Enum): @@ -87,26 +91,26 @@ def __init__(self, self.RECORD = record # Load the drone properties from the .urdf file. self.MASS, \ - self.L, \ - self.THRUST2WEIGHT_RATIO, \ - self.J, \ - self.J_INV, \ - self.KF, \ - self.KM, \ - self.COLLISION_H, \ - self.COLLISION_R, \ - self.COLLISION_Z_OFFSET, \ - self.MAX_SPEED_KMH, \ - self.GND_EFF_COEFF, \ - self.PROP_RADIUS, \ - self.DRAG_COEFF, \ - self.DW_COEFF_1, \ - self.DW_COEFF_2, \ - self.DW_COEFF_3, \ - self.PWM2RPM_SCALE, \ - self.PWM2RPM_CONST, \ - self.MIN_PWM, \ - self.MAX_PWM = self._parse_urdf_parameters(self.URDF_PATH) + self.L, \ + self.THRUST2WEIGHT_RATIO, \ + self.J, \ + self.J_INV, \ + self.KF, \ + self.KM, \ + self.COLLISION_H, \ + self.COLLISION_R, \ + self.COLLISION_Z_OFFSET, \ + self.MAX_SPEED_KMH, \ + self.GND_EFF_COEFF, \ + self.PROP_RADIUS, \ + self.DRAG_COEFF, \ + self.DW_COEFF_1, \ + self.DW_COEFF_2, \ + self.DW_COEFF_3, \ + self.PWM2RPM_SCALE, \ + self.PWM2RPM_CONST, \ + self.MIN_PWM, \ + self.MAX_PWM = self._parse_urdf_parameters(self.URDF_PATH) self.GROUND_PLANE_Z = -0.05 if verbose: print( @@ -127,11 +131,11 @@ def __init__(self, self.GRAVITY = self.GRAVITY_ACC * self.MASS self.HOVER_RPM = np.sqrt(self.GRAVITY / (4 * self.KF)) self.MAX_RPM = np.sqrt((self.THRUST2WEIGHT_RATIO * self.GRAVITY) / (4 * self.KF)) - self.MAX_THRUST = (4 * self.KF * self.MAX_RPM**2) - self.MAX_XY_TORQUE = (self.L * self.KF * self.MAX_RPM**2) - self.MAX_Z_TORQUE = (2 * self.KM * self.MAX_RPM**2) + self.MAX_THRUST = (4 * self.KF * self.MAX_RPM ** 2) + self.MAX_XY_TORQUE = (self.L * self.KF * self.MAX_RPM ** 2) + self.MAX_Z_TORQUE = (2 * self.KM * self.MAX_RPM ** 2) self.GND_EFF_H_CLIP = 0.25 * self.PROP_RADIUS * np.sqrt( - (15 * self.MAX_RPM**2 * self.KF * self.GND_EFF_COEFF) / self.MAX_THRUST) + (15 * self.MAX_RPM ** 2 * self.KF * self.GND_EFF_COEFF) / self.MAX_THRUST) # BenchmarkEnv constructor. super().__init__(gui=gui, verbose=verbose, **kwargs) # Connect to PyBullet. @@ -180,6 +184,10 @@ def __init__(self, np.ones(self.NUM_DRONES) * (self.COLLISION_H / 2 - self.COLLISION_Z_OFFSET) ]).transpose().reshape(self.NUM_DRONES, 3) self.INIT_RPYS = np.zeros((self.NUM_DRONES, 3)) + if physics == Physics.RK4: + self.setup_rk4_dynamics_expression() + elif physics == Physics.DYN_2D: + self.setup_dynamics_2d_expression() def close(self): '''Terminates the environment.''' @@ -212,7 +220,7 @@ def _reset_simulation(self): self.rpy = np.zeros((self.NUM_DRONES, 3)) self.vel = np.zeros((self.NUM_DRONES, 3)) self.ang_v = np.zeros((self.NUM_DRONES, 3)) - if self.PHYSICS == Physics.DYN: + if self.PHYSICS == Physics.DYN or self.PHYSICS == Physics.RK4 or self.PHYSICS == Physics.DYN_2D: self.rpy_rates = np.zeros((self.NUM_DRONES, 3)) # Set PyBullet's parameters. p.resetSimulation(physicsClientId=self.PYB_CLIENT) @@ -238,7 +246,7 @@ def _reset_simulation(self): self._update_and_store_kinematic_information() # Start video recording. self._start_video_recording() - # # Show frame of references of drones, will severly slow down the GUI. + # # Show frame of references of drones, will severely slow down the GUI. # for i in range(self.NUM_DRONES): # if gui: # self._show_drone_local_axes(i) @@ -252,22 +260,30 @@ def _advance_simulation(self, clipped_action, disturbance_force=None): `_preprocess_action()` in each subclass. disturbance_force (ndarray, optional): Disturbance force, applied to all drones. ''' - clipped_action = np.reshape(clipped_action, (self.NUM_DRONES, 4)) + time_before_stepping = time.time() + # clipped_action = np.reshape(clipped_action, (self.NUM_DRONES, 4)) + clipped_action = np.expand_dims(clipped_action, axis=0) + # Repeat for as many as the aggregate physics steps. for _ in range(self.PYB_STEPS_PER_CTRL): # Update and store the drones kinematic info for certain # Between aggregate steps for certain types of update. if self.PYB_STEPS_PER_CTRL > 1 and self.PHYSICS in [ - Physics.DYN, Physics.PYB_GND, Physics.PYB_DRAG, - Physics.PYB_DW, Physics.PYB_GND_DRAG_DW + Physics.DYN, Physics.PYB_GND, Physics.PYB_DRAG, + Physics.PYB_DW, Physics.PYB_GND_DRAG_DW, Physics.RK4, Physics.DYN_2D ]: self._update_and_store_kinematic_information() # Step the simulation using the desired physics update. for i in range(self.NUM_DRONES): + rpm = self._preprocess_control(clipped_action[i, :]) if self.PHYSICS == Physics.PYB: - self._physics(clipped_action[i, :], i) + self._physics(rpm, i) elif self.PHYSICS == Physics.DYN: self._dynamics(clipped_action[i, :], i) + elif self.PHYSICS == Physics.DYN_2D: + self._dynamics_2d(rpm, i) + elif self.PHYSICS == Physics.RK4: + self._dynamics_rk4(clipped_action[i, :], i) elif self.PHYSICS == Physics.PYB_GND: self._physics(clipped_action[i, :], i) self._ground_effect(clipped_action[i, :], i) @@ -293,12 +309,15 @@ def _advance_simulation(self, clipped_action, disturbance_force=None): flags=p.WORLD_FRAME, physicsClientId=self.PYB_CLIENT) # PyBullet computes the new state, unless Physics.DYN. - if self.PHYSICS != Physics.DYN: + if self.PHYSICS != Physics.DYN and self.PHYSICS != Physics.RK4 and self.PHYSICS != Physics.DYN_2D: p.stepSimulation(physicsClientId=self.PYB_CLIENT) # Save the last applied action (e.g. to compute drag). self.last_clipped_action = clipped_action - # Update and store the drones kinematic information. - self._update_and_store_kinematic_information() + # Update and store the drones kinematic information. + self._update_and_store_kinematic_information() + + time_after_stepping = time.time() + # print('time stepping', time_after_stepping - time_before_stepping) def render(self, mode='human', close=False): '''Prints a textual output of the environment. @@ -309,7 +328,8 @@ def render(self, mode='human', close=False): ''' if self.first_render_call and not self.GUI: print( - '[WARNING] BaseAviary.render() is implemented as text-only, re-initialize the environment using Aviary(gui=True) to use PyBullet\'s graphical interface' + '[WARNING] BaseAviary.render() is implemented as text-only, re-initialize the environment using ' + 'Aviary(gui=True) to use PyBullet\'s graphical interface' ) self.first_render_call = False if self.VERBOSE: @@ -318,8 +338,8 @@ def render(self, mode='human', close=False): self.pyb_step_counter), '——— wall-clock time {:.1f}s,'.format(time.time() - self.RESET_TIME), 'simulation time {:.1f}s@{:d}Hz ({:.2f}x)'.format( - self.pyb_step_counter * self.TIMESTEP, self.SIM_FREQ, - (self.pyb_step_counter * self.TIMESTEP) / (time.time() - self.RESET_TIME))) + self.pyb_step_counter * self.PYB_TIMESTEP, self.SIM_FREQ, + (self.pyb_step_counter * self.PYB_TIMESTEP) / (time.time() - self.RESET_TIME))) for i in range(self.NUM_DRONES): print( '[INFO] BaseAviary.render() ——— drone {:d}'.format(i), @@ -357,11 +377,13 @@ def _start_video_recording(self): if self.RECORD and self.GUI: self.VIDEO_ID = p.startStateLogging( loggingType=p.STATE_LOGGING_VIDEO_MP4, - fileName=os.path.join(self.output_dir, 'videos/video-{}.mp4'.format(datetime.now().strftime('%m.%d.%Y_%H.%M.%S'))), + fileName=os.path.join(self.output_dir, + 'videos/video-{}.mp4'.format(datetime.now().strftime('%m.%d.%Y_%H.%M.%S'))), physicsClientId=self.PYB_CLIENT) if self.RECORD and not self.GUI: self.FRAME_NUM = 0 - self.IMG_PATH = os.path.join(self.output_dir, 'quadrotor_videos/video-{}/'.format(datetime.now().strftime('%m.%d.%Y_%H.%M.%S'))) + self.IMG_PATH = os.path.join(self.output_dir, 'quadrotor_videos/video-{}/'.format( + datetime.now().strftime('%m.%d.%Y_%H.%M.%S'))) os.makedirs(os.path.dirname(self.IMG_PATH), exist_ok=True) def _get_drone_state_vector(self, nth_drone): @@ -371,7 +393,7 @@ def _get_drone_state_vector(self, nth_drone): nth_drone (int): The ordinal number/position of the desired drone in list self.DRONE_IDS. Returns: - ndarray. (20,)-shaped array of floats containing the state vector of the n-th drone. + ndarray. (20, )-shaped array of floats containing the state vector of the n-th drone. Check the only line in this method and `_update_and_store_kinematic_information()` to understand its format. ''' @@ -380,7 +402,8 @@ def _get_drone_state_vector(self, nth_drone): self.rpy[nth_drone, :], self.vel[nth_drone, :], self.ang_v[nth_drone, :], self.last_clipped_action[nth_drone, :] ]) - return state.reshape(20,) + # state.reshape(20, ) + return state.copy() def _physics(self, rpm, nth_drone): '''Base PyBullet physics implementation. @@ -389,8 +412,8 @@ def _physics(self, rpm, nth_drone): rpm (ndarray): (4)-shaped array of ints containing the RPMs values of the 4 motors. nth_drone (int): The ordinal number/position of the desired drone in list self.DRONE_IDS. ''' - forces = np.array(rpm**2) * self.KF - torques = np.array(rpm**2) * self.KM + forces = np.array(rpm ** 2) * self.KF + torques = np.array(rpm ** 2) * self.KM z_torque = (-torques[0] + torques[1] - torques[2] + torques[3]) for i in range(4): p.applyExternalForce(self.DRONE_IDS[nth_drone], @@ -427,8 +450,8 @@ def _ground_effect(self, rpm, nth_drone): link_states[3, 0][2] ]) prop_heights = np.clip(prop_heights, self.GND_EFF_H_CLIP, np.inf) - gnd_effects = np.array(rpm**2) * self.KF * self.GND_EFF_COEFF \ - * (self.PROP_RADIUS / (4 * prop_heights))**2 + gnd_effects = np.array(rpm ** 2) * self.KF * self.GND_EFF_COEFF \ + * (self.PROP_RADIUS / (4 * prop_heights)) ** 2 if np.abs(self.rpy[nth_drone, 0]) < np.pi / 2 and np.abs( self.rpy[nth_drone, 1]) < np.pi / 2: for i in range(4): @@ -477,9 +500,9 @@ def _downwash(self, nth_drone): delta_xy = np.linalg.norm( np.array(self.pos[i, 0:2]) - np.array(self.pos[nth_drone, 0:2])) if delta_z > 0 and delta_xy < 10: # Ignore drones more than 10 meters away - alpha = self.DW_COEFF_1 * (self.PROP_RADIUS / (4 * delta_z))**2 + alpha = self.DW_COEFF_1 * (self.PROP_RADIUS / (4 * delta_z)) ** 2 beta = self.DW_COEFF_2 * delta_z + self.DW_COEFF_3 - downwash = [0, 0, -alpha * np.exp(-.5 * (delta_xy / beta)**2)] + downwash = [0, 0, -alpha * np.exp(-.5 * (delta_xy / beta) ** 2)] p.applyExternalForce(self.DRONE_IDS[nth_drone], 4, forceObj=downwash, @@ -504,11 +527,11 @@ def _dynamics(self, rpm, nth_drone): rpy_rates = self.rpy_rates[nth_drone, :] rotation = np.array(p.getMatrixFromQuaternion(quat)).reshape(3, 3) # Compute forces and torques. - forces = np.array(rpm**2) * self.KF + forces = np.array(rpm ** 2) * self.KF thrust = np.array([0, 0, np.sum(forces)]) thrust_world_frame = np.dot(rotation, thrust) force_world_frame = thrust_world_frame - np.array([0, 0, self.GRAVITY]) - z_torques = np.array(rpm**2) * self.KM + z_torques = np.array(rpm ** 2) * self.KM z_torque = (-z_torques[0] + z_torques[1] - z_torques[2] + z_torques[3]) if self.DRONE_MODEL == DroneModel.CF2X: x_torque = (forces[0] + forces[1] - forces[2] - forces[3]) * (self.L / np.sqrt(2)) @@ -521,10 +544,56 @@ def _dynamics(self, rpm, nth_drone): rpy_rates_deriv = np.dot(self.J_INV, torques) no_pybullet_dyn_accs = force_world_frame / self.MASS # Update state. - vel = vel + self.TIMESTEP * no_pybullet_dyn_accs - rpy_rates = rpy_rates + self.TIMESTEP * rpy_rates_deriv - pos = pos + self.TIMESTEP * vel - rpy = rpy + self.TIMESTEP * rpy_rates + vel = vel + self.PYB_TIMESTEP * no_pybullet_dyn_accs + rpy_rates = rpy_rates + self.PYB_TIMESTEP * rpy_rates_deriv + pos = pos + self.PYB_TIMESTEP * vel + rpy = rpy + self.PYB_TIMESTEP * rpy_rates + # Set PyBullet's state. + p.resetBasePositionAndOrientation(self.DRONE_IDS[nth_drone], + pos, + p.getQuaternionFromEuler(rpy), + physicsClientId=self.PYB_CLIENT) + # Note: the base's velocity only stored and not used # + p.resetBaseVelocity( + self.DRONE_IDS[nth_drone], + vel, + rpy_rates, # ang_vel not computed by DYN + physicsClientId=self.PYB_CLIENT) + # Store the roll, pitch, yaw rates for the next step # + self.rpy_rates[nth_drone, :] = rpy_rates + + def _dynamics_rk4(self, rpm, nth_drone): + '''Explicit dynamics implementation. + + Based on code written at the Dynamic Systems Lab by James Xu. + + Args: + rpm (ndarray): (4)-shaped array of ints containing the RPMs values of the 4 motors. + nth_drone (int): The ordinal number/position of the desired drone in list self.DRONE_IDS. + ''' + # Current state. + pos = self.pos[nth_drone, :] + # quat = self.quat[nth_drone, :] + rpy = self.rpy[nth_drone, :] + vel = self.vel[nth_drone, :] + rpy_rates = self.rpy_rates[nth_drone, :] + # rotation = np.array(p.getMatrixFromQuaternion(quat)).reshape(3, 3) + # Compute forces and torques. + forces = np.array(rpm ** 2) * self.KF + # Update state with discrete time dynamics. + state = np.hstack([pos[0], vel[0], pos[1], vel[1], pos[2], vel[2], + rpy[0], rpy[1], rpy[2], rpy_rates[0], rpy_rates[1], rpy_rates[2]]) + input = np.array([forces[0], forces[1], forces[2], forces[3]]) + + # update state with RK4 + next_state = self.fd_func(x0=state, p=input)['xf'] + + pos = np.array([next_state[0], next_state[2], next_state[4]]) + rpy = np.array([next_state[6], next_state[7], next_state[8]]) + vel = np.array([next_state[1], next_state[3], next_state[5]]) + rpy_rates = np.array([next_state[9], next_state[10], next_state[11]]) + rpy_rates = np.squeeze(rpy_rates) + # Set PyBullet's state. p.resetBasePositionAndOrientation(self.DRONE_IDS[nth_drone], pos, @@ -539,6 +608,155 @@ def _dynamics(self, rpm, nth_drone): # Store the roll, pitch, yaw rates for the next step # self.rpy_rates[nth_drone, :] = rpy_rates + def setup_rk4_dynamics_expression(self): + nx, nu = 12, 4 + gamma = self.KM / self.KF + z = cs.MX.sym('z') + z_dot = cs.MX.sym('z_dot') + x = cs.MX.sym('x') + y = cs.MX.sym('y') + phi = cs.MX.sym('phi') # Roll + theta = cs.MX.sym('theta') # Pitch + psi = cs.MX.sym('psi') # Yaw + x_dot = cs.MX.sym('x_dot') + y_dot = cs.MX.sym('y_dot') + p_body = cs.MX.sym('p') # Body frame roll rate + q_body = cs.MX.sym('q') # body frame pith rate + r_body = cs.MX.sym('r') # body frame yaw rate + # PyBullet Euler angles use the SDFormat for rotation matrices. + Rob = csRotXYZ(phi, theta, psi) # rotation matrix transforming a vector in the body frame to the world frame. + + # Define state variables. + X = cs.vertcat(x, x_dot, y, y_dot, z, z_dot, phi, theta, psi, p_body, q_body, r_body) + + # Define inputs. + f1 = cs.MX.sym('f1') + f2 = cs.MX.sym('f2') + f3 = cs.MX.sym('f3') + f4 = cs.MX.sym('f4') + U = cs.vertcat(f1, f2, f3, f4) + + # From Ch. 2 of Luis, Carlos, and Jérôme Le Ny. 'Design of a trajectory tracking controller for a + # nanoquadcopter.' arXiv preprint arXiv:1608.05786 (2016). + + # Defining the dynamics function. + # We are using the velocity of the base wrt to the world frame expressed in the world frame. + # Note that the reference expresses this in the body frame. + oVdot_cg_o = Rob @ cs.vertcat(0, 0, f1 + f2 + f3 + f4) / self.MASS - cs.vertcat(0, 0, self.GRAVITY_ACC) + pos_ddot = oVdot_cg_o + pos_dot = cs.vertcat(x_dot, y_dot, z_dot) + Mb = cs.vertcat(self.L / cs.sqrt(2.0) * (f1 + f2 - f3 - f4), + self.L / cs.sqrt(2.0) * (-f1 + f2 + f3 - f4), + gamma * (-f1 + f2 - f3 + f4)) + rate_dot = self.J_INV @ ( + Mb - (cs.skew(cs.vertcat(p_body, q_body, r_body)) @ self.J @ cs.vertcat(p_body, q_body, r_body))) + ang_dot = cs.blockcat([[1, cs.sin(phi) * cs.tan(theta), cs.cos(phi) * cs.tan(theta)], + [0, cs.cos(phi), -cs.sin(phi)], + [0, cs.sin(phi) / cs.cos(theta), cs.cos(phi) / cs.cos(theta)]]) @ cs.vertcat(p_body, + q_body, + r_body) + X_dot = cs.vertcat(pos_dot[0], pos_ddot[0], pos_dot[1], pos_ddot[1], pos_dot[2], pos_ddot[2], ang_dot, rate_dot) + self.X_dot_fun = cs.Function("X_dot", [X, U], [X_dot]) + self.fd_func = cs.integrator('fd', 'rk', {'x': X, + 'p': U, + 'ode': X_dot}, {'tf': self.PYB_TIMESTEP}) + + def _dynamics_2d(self, rpm, nth_drone): + '''Explicit dynamics implementation. + + Based on the identified model. + + Args: + rpm (ndarray): (4)-shaped array of ints containing the RPMs values of the 4 motors. + nth_drone (int): The ordinal number/position of the desired drone in list self.DRONE_IDS. + ''' + # Current state. + pos = self.pos[nth_drone, :] + # quat = self.quat[nth_drone, :] + rpy = self.rpy[nth_drone, :] + vel = self.vel[nth_drone, :] + ang_v = self.ang_v[nth_drone, :] + rpy_rates = self.rpy_rates[nth_drone, :] + # rotation = np.array(p.getMatrixFromQuaternion(quat)).reshape(3, 3) + # Compute forces and torques. + forces = np.array(rpm ** 2) * self.KF + # Update state with discrete time dynamics. + state = np.hstack([pos[0], vel[0], pos[1], vel[1], pos[2], vel[2], + rpy[0], rpy[1], rpy[2], ang_v[0], ang_v[1], ang_v[2]]) + action = np.array([forces[0], forces[1], forces[2], forces[3]]) + + # update state with RK4 + # next_state = self.fd_func(x0=state, p=input)['xf'].full()[:, 0] + X_dot = self.X_dot_fun(state, action).full()[:, 0] + next_state = state + X_dot*self.PYB_TIMESTEP + + pos = np.array([next_state[0], 0, next_state[4]]) + rpy = np.array([0, next_state[7], 0]) + vel = np.array([next_state[1], 0, next_state[5]]) + ang_v = np.array([0, next_state[10], 0]) + ang_v = np.squeeze(ang_v) + + # Set PyBullet's state. + p.resetBasePositionAndOrientation(self.DRONE_IDS[nth_drone], + pos, + p.getQuaternionFromEuler(rpy), + physicsClientId=self.PYB_CLIENT) + # Note: the base's velocity only stored and not used # + p.resetBaseVelocity(self.DRONE_IDS[nth_drone], + vel, + ang_v, # ang_vel not computed by DYN + physicsClientId=self.PYB_CLIENT) + # Store the roll, pitch, yaw rates for the next step # + self.rpy_rates[nth_drone, :] = X_dot[6:9] + + def setup_dynamics_2d_expression(self): + gamma = self.KM / self.KF + + # Casadi states + z = cs.MX.sym('z') + x = cs.MX.sym('x') + y = cs.MX.sym('y') + z_dot = cs.MX.sym('z_dot') + x_dot = cs.MX.sym('x_dot') + y_dot = cs.MX.sym('y_dot') + phi = cs.MX.sym('phi') # Roll + theta = cs.MX.sym('theta') # Pitch + psi = cs.MX.sym('psi') # Yaw + p_body = cs.MX.sym('p') # Body frame roll rate + q_body = cs.MX.sym('q') # body frame pitch rate + r_body = cs.MX.sym('r') # body frame yaw rate + X = cs.vertcat(x, x_dot, y, y_dot, z, z_dot, phi, theta, psi, p_body, q_body, r_body) + + # Define inputs. + f1 = cs.MX.sym('f1') + f2 = cs.MX.sym('f2') + f3 = cs.MX.sym('f3') + f4 = cs.MX.sym('f4') + U = cs.vertcat(f1, f2, f3, f4) + + # PyBullet Euler angles use the SDFormat for rotation matrices. + Rob = csRotXYZ(phi, theta, psi) # rotation matrix transforming a vector in the body frame to the world frame. + + # From Ch. 2 of Luis, Carlos, and Jérôme Le Ny. 'Design of a trajectory tracking controller for a + # nanoquadcopter.' arXiv preprint arXiv:1608.05786 (2016). + + # Defining the dynamics function. + # We are using the velocity of the base wrt to the world frame expressed in the world frame. + # Note that the reference expresses this in the body frame. + pos_ddot = Rob @ cs.vertcat(0, 0, f1 + f2 + f3 + f4) / self.MASS - cs.vertcat(0, 0, self.GRAVITY_ACC) + pos_dot = cs.vertcat(x_dot, y_dot, z_dot) + Mb = cs.vertcat(self.L / cs.sqrt(2.0) * (f1 + f2 - f3 - f4), + self.L / cs.sqrt(2.0) * (-f1 + f2 + f3 - f4), + gamma * (-f1 + f2 - f3 + f4)) + rate_dot = self.J_INV @ ( + Mb - (cs.skew(cs.vertcat(p_body, q_body, r_body)) @ self.J @ cs.vertcat(p_body, q_body, r_body))) + ang_dot = (cs.blockcat([[1, cs.sin(phi) * cs.tan(theta), cs.cos(phi) * cs.tan(theta)], + [0, cs.cos(phi), -cs.sin(phi)], + [0, cs.sin(phi) / cs.cos(theta), cs.cos(phi) / cs.cos(theta)]]) @ + cs.vertcat(p_body, q_body, r_body)) + X_dot = cs.vertcat(pos_dot[0], pos_ddot[0], pos_dot[1], pos_ddot[1], pos_dot[2], pos_ddot[2], ang_dot, rate_dot) + self.X_dot_fun = cs.Function("X_dot", [X, U], [X_dot]) + def _show_drone_local_axes(self, nth_drone): '''Draws the local frame of the n-th drone in PyBullet's GUI. @@ -609,5 +827,5 @@ def _parse_urdf_parameters(self, file_name): MIN_PWM = float(URDF_TREE[0].attrib['pwm_min']) MAX_PWM = float(URDF_TREE[0].attrib['pwm_max']) return M, L, THRUST2WEIGHT_RATIO, J, J_INV, KF, KM, COLLISION_H, COLLISION_R, COLLISION_Z_OFFSET, MAX_SPEED_KMH, \ - GND_EFF_COEFF, PROP_RADIUS, DRAG_COEFF, DW_COEFF_1, DW_COEFF_2, DW_COEFF_3, \ - PWM2RPM_SCALE, PWM2RPM_CONST, MIN_PWM, MAX_PWM + GND_EFF_COEFF, PROP_RADIUS, DRAG_COEFF, DW_COEFF_1, DW_COEFF_2, DW_COEFF_3, \ + PWM2RPM_SCALE, PWM2RPM_CONST, MIN_PWM, MAX_PWM \ No newline at end of file diff --git a/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py b/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py index 493383550..7621728b9 100644 --- a/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py +++ b/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py @@ -197,7 +197,7 @@ def __init__(self, if (self.QUAD_TYPE == QuadType.ONE_D and len(info_mse_metric_state_weight) == 2) or \ (self.QUAD_TYPE == QuadType.TWO_D and len(info_mse_metric_state_weight) == 6) or \ (self.QUAD_TYPE == QuadType.THREE_D and len(info_mse_metric_state_weight) == 12) or \ - (self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE and len(info_mse_metric_state_weight) == 5): + (self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE and len(info_mse_metric_state_weight) == 6): self.info_mse_metric_state_weight = np.array(info_mse_metric_state_weight, ndmin=1, dtype=float) else: raise ValueError('[ERROR] in Quadrotor.__init__(), wrong info_mse_metric_state_weight argument size.') @@ -344,7 +344,7 @@ def __init__(self, # Set attitude controller if quadtype is QuadType.TWO_D_ATTITUDE if self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE: - self.attitude_control = AttitudeControl(self.CTRL_TIMESTEP) + self.attitude_control = AttitudeControl(self.CTRL_TIMESTEP, self.PYB_TIMESTEP) # Set prior/symbolic info. self._setup_symbolic() @@ -438,7 +438,7 @@ def step(self, action): """ # Get the preprocessed rpm for each motor - rpm = super().before_step(action) + action = super().before_step(action) # Determine disturbance force. disturb_force = None @@ -468,7 +468,7 @@ def step(self, action): disturb_force = np.asarray(disturb_force).flatten() # Advance the simulation. - super()._advance_simulation(rpm, disturb_force) + super()._advance_simulation(action, disturb_force) # Standard Gym return. obs = self._get_observation() rew = self._get_reward() @@ -835,14 +835,17 @@ def _preprocess_control(self, action): if self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE: collective_thrust, pitch = action + # rpm = self.attitude_control._dslPIDAttitudeControl(individual_thrust, # self.quat[0], np.array([0, pitch, 0])) # input thrust is pwm # thrust_action = self.KF * rpm**2 # thrust_action = self.attitude_control._dslPIDAttitudeControl(self.attitude_control.pwm2thrust(thrust_c/3), # self.quat[0], np.array([0, pitch, 0])) # input thrust is in Newton # print(f"collective_thrust: {collective_thrust}, pitch: {pitch}") + thrust_action = self.attitude_control._dslPIDAttitudeControl(collective_thrust / 4, - self.quat[0], np.array([0, pitch, 0])) # input thrust is in Newton + self.quat[0], np.array([0, pitch, 0])) + # input thrust is in Newton thrust = np.array([thrust_action[0] + thrust_action[3], thrust_action[1] + thrust_action[2]]) thrust = np.clip(thrust, np.full(2, self.physical_action_bounds[0][0] / 2), np.full(2, self.physical_action_bounds[1][0] / 2)) @@ -851,11 +854,9 @@ def _preprocess_control(self, action): else: thrust = np.clip(action, self.physical_action_bounds[0], self.physical_action_bounds[1]) self.current_clipped_action = thrust - # print(sum(thrust)) # convert to quad motor rpm commands pwm = cmd2pwm(thrust, self.PWM2RPM_SCALE, self.PWM2RPM_CONST, self.KF, self.MIN_PWM, self.MAX_PWM) rpm = pwm2rpm(pwm, self.PWM2RPM_SCALE, self.PWM2RPM_CONST) - return rpm def normalize_action(self, action): diff --git a/safe_control_gym/envs/gym_pybullet_drones/quadrotor_utils.py b/safe_control_gym/envs/gym_pybullet_drones/quadrotor_utils.py index 5669ac144..33d91cfb8 100644 --- a/safe_control_gym/envs/gym_pybullet_drones/quadrotor_utils.py +++ b/safe_control_gym/envs/gym_pybullet_drones/quadrotor_utils.py @@ -69,6 +69,7 @@ class AttitudeControl(ABC): def __init__(self, control_timestep, + sim_timestep, g: float = 9.8, kf: float = 3.16e-10, km: float = 7.94e-12, @@ -84,6 +85,7 @@ def __init__(self, Args: control_timestep (float): The time step at which control is computed. + sim_timestep (float): The time step at which simulation is carried out. g (float, optional): The gravitational acceleration in m/s^2. kf (float, optional): Thrust coefficient. km (float, optional): Torque coefficient. @@ -116,6 +118,7 @@ def __init__(self, self.integral_rpy_e = np.zeros(3) self.control_timestep = control_timestep + self.sim_timestep = sim_timestep def reset(self): """Reinitialize just the controller before a new run.""" @@ -149,6 +152,8 @@ def _dslPIDAttitudeControl(self, (4,1)-shaped array of integers containing the RPMs to apply to each of the 4 motors. """ + # control_timestep = self.control_timestep + sim_timestep = self.sim_timestep 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() @@ -156,9 +161,9 @@ def _dslPIDAttitudeControl(self, 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 + rpy_rates_e = target_rpy_rates - (cur_rpy - self.last_rpy) / sim_timestep self.last_rpy = cur_rpy - self.integral_rpy_e = self.integral_rpy_e - rot_e * self.control_timestep + self.integral_rpy_e = self.integral_rpy_e - rot_e * sim_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 #################################### diff --git a/safe_control_gym/experiments/base_experiment.py b/safe_control_gym/experiments/base_experiment.py index ece40bcdd..06cdab983 100644 --- a/safe_control_gym/experiments/base_experiment.py +++ b/safe_control_gym/experiments/base_experiment.py @@ -1,4 +1,4 @@ -'''To standardize training/evaluation interface.''' +"""To standardize training/evaluation interface.""" from collections import defaultdict from copy import deepcopy @@ -14,7 +14,7 @@ class BaseExperiment: - '''Generic Experiment Class.''' + """Generic Experiment Class.""" def __init__(self, env, @@ -23,15 +23,15 @@ def __init__(self, safety_filter=None, verbose: bool = False, ): - '''Creates a generic experiment class to run evaluations and collect standard metrics. + """Creates a generic experiment class to run evaluations and collect standard metrics. Args: env (BenchmarkEnv): The environment for the task. ctrl (BaseController): The controller for the task. train_env (BenchmarkEnv): The environment used for training. safety_filter (BaseSafetyFilter): The safety filter to filter the controller. - verbose (bool, optional): If to suppress BaseExperiment print statetments. - ''' + verbose (bool, optional): If to suppress BaseExperiment print statements. + """ self.metric_extractor = MetricExtractor() self.verbose = verbose @@ -49,7 +49,7 @@ def __init__(self, self.reset() def run_evaluation(self, training=False, n_episodes=None, n_steps=None, done_on_max_steps=None, log_freq=None, verbose=True, **kwargs): - '''Evaluate a trained controller. + """Evaluate a trained controller. Args: training (bool): Whether run_evaluation is being run as part of a training loop or not. @@ -60,7 +60,7 @@ def run_evaluation(self, training=False, n_episodes=None, n_steps=None, done_on_ Returns: trajs_data (dict): The raw data from the executed runs. metrics (dict): The metrics calculated from the raw data. - ''' + """ if not training: self.reset() @@ -79,7 +79,7 @@ def run_evaluation(self, training=False, n_episodes=None, n_steps=None, done_on_ return dict(trajs_data), metrics def _execute_evaluations(self, n_episodes=None, n_steps=None, done_on_max_steps=None, log_freq=None, seeds=None): - '''Runs the experiments and collects all the required data. + """Runs the experiments and collects all the required data. Args: n_episodes (int): Number of runs to execute. @@ -89,7 +89,7 @@ def _execute_evaluations(self, n_episodes=None, n_steps=None, done_on_max_steps= Returns: trajs_data (defaultdict(list)): The raw data from the executed runs. - ''' + """ if n_episodes is None and n_steps is None: raise ValueError('One of n_episodes or n_steps must be defined.') @@ -116,7 +116,7 @@ def _execute_evaluations(self, n_episodes=None, n_steps=None, done_on_max_steps= # try: # action = self._select_action(obs=obs, info=info) # except RuntimeError: - # print('RuntimeError in selecting action, using last avaible action') + # print('RuntimeError in selecting action, using last available action') # if 'action' in locals(): # action = action # use the previous action # else: @@ -168,7 +168,7 @@ def _execute_evaluations(self, n_episodes=None, n_steps=None, done_on_max_steps= return munchify(trajs_data) def _select_action(self, obs, info): - '''Determines the executed action using the controller and safety filter. + """Determines the executed action using the controller and safety filter. Args: obs (ndarray): The observation at this timestep. @@ -176,7 +176,7 @@ def _select_action(self, obs, info): Returns: action (ndarray): The action chosen by the controller and safety filter. - ''' + """ action = self.ctrl.select_action(obs, info) if self.safety_filter is not None: @@ -188,7 +188,7 @@ def _select_action(self, obs, info): return action def _evaluation_reset(self, ctrl_data, sf_data, seed=None): - '''Resets the evaluation between runs. + """Resets the evaluation between runs. Args: ctrl_data (defaultdict): The controller specific data collected during execution. @@ -198,7 +198,7 @@ def _evaluation_reset(self, ctrl_data, sf_data, seed=None): Returns: obs (ndarray): The initial observation. info (dict): The initial info. - ''' + """ if self.env.INFO_IN_RESET: obs, info = self.env.reset(seed=seed) else: @@ -216,11 +216,11 @@ def _evaluation_reset(self, ctrl_data, sf_data, seed=None): return obs, info def launch_training(self, **kwargs): - '''Since the learning loop varies among controllers, can only delegate to its own `learn()` method. + """Since the learning loop varies among controllers, can only delegate to its own `learn()` method. Returns: trajs_data (defaultdict(list)): The raw data from the training. - ''' + """ self.reset() self.ctrl.learn(env=self.train_env, **kwargs) @@ -236,21 +236,21 @@ def launch_training(self, **kwargs): return dict(trajs_data) def compute_metrics(self, trajs_data): - '''Compute all standard metrics on the given trajectory data. + """Compute all standard metrics on the given trajectory data. Args: trajs_data (defaultdict(list)): The raw data from the executed runs. Returns: metrics (dict): The metrics calculated from the raw data. - ''' + """ metrics = self.metric_extractor.compute_metrics(data=trajs_data, verbose=self.verbose) return metrics def reset(self): - '''Resets the environments, controller, and safety filter to prepare for training or evaluation.''' + """Resets the environments, controller, and safety filter to prepare for training or evaluation.""" self.env.reset() self.env.clear_data() @@ -264,7 +264,7 @@ def reset(self): self.train_env.clear_data() def close(self): - '''Closes the environments, controller, and safety filter.''' + """Closes the environments, controller, and safety filter.""" self.env.close() self.ctrl.close() @@ -276,12 +276,12 @@ def close(self): self.train_env.close() def load(self, ctrl_path=None, safety_filter_path=None): - '''Restores model of the controller and/or safety filter given checkpoint paths. + """Restores model of the controller and/or safety filter given checkpoint paths. Args: ctrl_path (str): The path used to load the controller's model. safety_filter_path (str): The path used to load the safety_filter's model. - ''' + """ if ctrl_path is not None: self.ctrl.load(ctrl_path) @@ -289,12 +289,12 @@ def load(self, ctrl_path=None, safety_filter_path=None): self.safety_filter.load(safety_filter_path) def save(self, ctrl_path=None, safety_filter_path=None): - '''Saves the model of the controller and/or safety filter given checkpoint paths. + """Saves the model of the controller and/or safety filter given checkpoint paths. Args: ctrl_path (str): The path used to save the controller's model. safety_filter_path (str): The path used to save the safety_filter's model. - ''' + """ if ctrl_path is not None: self.ctrl.save(ctrl_path) @@ -303,13 +303,13 @@ def save(self, ctrl_path=None, safety_filter_path=None): class RecordDataWrapper(gym.Wrapper): - '''A wrapper to standardizes logging for benchmark envs. + """A wrapper to standardizes logging for benchmark envs. currently saved info * obs, reward, done, info, action * env.state, env.current_physical_action, env.current_noisy_physical_action, env.current_clipped_action - ''' + """ def __init__(self, env): super().__init__(env) @@ -317,7 +317,7 @@ def __init__(self, env): self.clear_data() def save_data(self): - '''Saves the current self.episode_data to self.data and clears self.episode_data.''' + """Saves the current self.episode_data to self.data and clears self.episode_data.""" if self.episode_data: # save to data container for key, ep_val in self.episode_data.items(): @@ -329,12 +329,12 @@ def save_data(self): self.episode_data = defaultdict(list) def clear_data(self): - '''Clears all data in self.data and self.episode_data.''' + """Clears all data in self.data and self.episode_data.""" self.data = defaultdict(list) self.episode_data = defaultdict(list) def reset(self, **kwargs): - '''Wrapper for the gym.env reset function.''' + """Wrapper for the gym.env reset function.""" if self.env.INFO_IN_RESET: obs, info = self.env.reset(**kwargs) @@ -358,7 +358,7 @@ def reset(self, **kwargs): return obs def step(self, action): - '''Wrapper for the gym.env step function.''' + """Wrapper for the gym.env step function.""" obs, reward, done, info = self.env.step(action) # save to episode data container @@ -382,7 +382,7 @@ def step(self, action): class MetricExtractor: - '''A utility class that computes metrics given collected trajectory data. + """A utility class that computes metrics given collected trajectory data. metrics that can be derived * episode lengths, episode total rewards/returns @@ -391,18 +391,18 @@ class MetricExtractor: (0/1 for each episode, failure rate = #occurrences/#episodes) * episode constraint violation steps (how many constraint violations happened in each episode) - ''' + """ def compute_metrics(self, data, verbose=False): - '''Compute all standard metrics on the given trajectory data. + """Compute all standard metrics on the given trajectory data. Args: data (defaultdict(list)): The raw data from the executed runs. - verbose (bool, optional): If to suppress compute_metrics print statetments. + verbose (bool, optional): If to suppress compute_metrics print statements. Returns: metrics (dict): The metrics calculated from the raw data. - ''' + """ self.data = data self.verbose = verbose @@ -429,7 +429,7 @@ def compute_metrics(self, data, verbose=False): return metrics def get_episode_data(self, key, postprocess_func=lambda x: x, exponentiate=False): - '''Extract data field from recorded trajectory data, optionally postprocess each episode data (e.g. get sum). + """Extract data field from recorded trajectory data, optionally postprocess each episode data (e.g. get sum). Args: key (str): The key of the data to retrieve. @@ -437,7 +437,7 @@ def get_episode_data(self, key, postprocess_func=lambda x: x, exponentiate=False Returns: episode_data (list): The desired data. - ''' + """ if key in self.data: if exponentiate: @@ -463,52 +463,52 @@ def get_episode_data(self, key, postprocess_func=lambda x: x, exponentiate=False return episode_data def get_episode_lengths(self): - '''Total length of episodes. + """Total length of episodes. Returns: episode_lengths (list): The lengths of each episode. - ''' + """ return self.get_episode_data('length', postprocess_func=sum) def get_episode_returns(self, exponentiate=False): - '''Total reward/return of episodes. + """Total reward/return of episodes. Returns: episode_rewards (list): The total reward of each episode. - ''' + """ return self.get_episode_data('reward', postprocess_func=sum, exponentiate=exponentiate) def get_episode_exponentiated_returns(self): - '''Total reward/return of episodes. + """Total reward/return of episodes. Returns: episode_rewards (list): The total reward of each episode. - ''' + """ return self.get_episode_data('reward', postprocess_func=sum) def get_episode_rmse(self): - '''Root mean square error of episodes. + """Root-mean-square error of episodes. Returns: episode_rmse (list): The total rmse of each episode. - ''' + """ return self.get_episode_data('mse', postprocess_func=lambda x: float(np.sqrt(np.mean(x)))) def get_episode_constraint_violations(self): - '''Occurence of any violation in episodes. + """Occurrence of any violation in episodes. Returns: episode_violated (list): Whether each episode had a constraint violation. - ''' + """ return self.get_episode_data('constraint_violation', postprocess_func=lambda x: float(any(x))) def get_episode_constraint_violation_steps(self): - '''Total violation steps of episodes. + """Total violation steps of episodes. Returns: episode_violations (list): The total number of constraint violations of each episode. - ''' + """ return self.get_episode_data('constraint_violation', postprocess_func=sum) diff --git a/safe_control_gym/experiments/train_rl_controller.py b/safe_control_gym/experiments/train_rl_controller.py index 53f4266dd..15682bca3 100644 --- a/safe_control_gym/experiments/train_rl_controller.py +++ b/safe_control_gym/experiments/train_rl_controller.py @@ -22,6 +22,7 @@ def train(): fac = ConfigFactory() config = fac.merge() config.algo_config['training'] = True + config.use_gpu = True shutil.rmtree(config.output_dir, ignore_errors=True) @@ -32,8 +33,7 @@ def train(): env_func = partial(make, config.task, output_dir=config.output_dir, - **config.task_config - ) + **config.task_config) # Create the controller/control_agent. ctrl = make(config.algo,