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 d0a5cd8f6..12eeaf4df 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 @@ -14,10 +14,10 @@ algo_config: critic_lr: 0.001 # runner args - max_env_steps: 540000 + max_env_steps: 480000 rollout_batch_size: 4 rollout_steps: 540 - eval_batch_size: 50 + eval_batch_size: 10 # misc log_interval: 10800 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 5f8bb1b11..c7d0dbb24 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,8 +2,8 @@ task_config: seed: 1337 info_in_reset: True ctrl_freq: 60 - pyb_freq: 1200 - physics: pyb + pyb_freq: 60 + physics: dyn_si quad_type: 4 normalized_rl_action_space: False @@ -20,42 +20,42 @@ task_config: init_state_randomization_info: init_x: distrib: 'uniform' - low: -0.02 - high: 0.02 + low: -0.05 + high: 0.05 init_x_dot: distrib: 'uniform' - low: -0.02 - high: 0.02 + low: -0.05 + high: 0.05 init_z: distrib: 'uniform' - low: -0.02 - high: 0.02 + low: -0.05 + high: 0.05 init_z_dot: distrib: 'uniform' - low: -0.02 - high: 0.02 + low: -0.05 + high: 0.05 init_theta: distrib: 'uniform' - low: -0.02 - high: 0.02 + low: -0.05 + high: 0.05 init_theta_dot: distrib: 'uniform' - low: -0.02 - high: 0.02 + low: -0.05 + high: 0.05 task: traj_tracking task_info: trajectory_type: figure8 - num_cycles: 1 + num_cycles: 2 trajectory_plane: 'xz' - trajectory_position_offset: [0, 1.2] + trajectory_position_offset: [0, 1.] trajectory_scale: 0.5 inertial_prop: M: 0.027 Iyy: 1.4e-05 - episode_len_sec: 10 + episode_len_sec: 9 cost: rl_reward obs_goal_horizon: 1 @@ -67,17 +67,17 @@ task_config: disturbances: observation: - disturbance_func: white_noise - std: [0.02, 0.02, 0.04, 0.04, 0.04, 0.1, 0., 0., 0., 0., 0., 0.] + std: [5.6e-05, 1.5e-02, 2.9e-05, 8.0e-03, 1.3e-03, 3.6e-01, 0., 0., 0., 0., 0., 0.] -# constraints: -# - constraint_form: default_constraint -# constrained_variable: state + 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] + - constraint_form: default_constraint + constrained_variable: input + upper_bounds: [0.47628, 0.4] + lower_bounds: [0.079, -0.4] 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 b43cb5cc4..d7e06b8a7 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 @@ -7,23 +7,21 @@ algo_config: # optim args train_interval: 100 train_batch_size: 256 - actor_lr: 0.001 - critic_lr: 0.001 - entropy_lr: 0.001 + actor_lr: 0.003 + critic_lr: 0.003 + entropy_lr: 0.003 # runner args - max_env_steps: 540000 + max_env_steps: 216000 warm_up_steps: 1000 rollout_batch_size: 4 - num_workers: 1 max_buffer_size: 54000 - deque_size: 50 - eval_batch_size: 50 + eval_batch_size: 10 # misc - log_interval: 10800 + log_interval: 5400 save_interval: 540000 num_checkpoints: 0 - eval_interval: 10800 + eval_interval: 5400 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 b968a24ca..bfa33c589 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 @@ -1,4 +1,3 @@ -algo: sac algo_config: # model args hidden_dim: 128 @@ -8,22 +7,20 @@ algo_config: # optim args train_interval: 100 train_batch_size: 256 - actor_lr: 0.001 - critic_lr: 0.001 + actor_lr: 0.003 + critic_lr: 0.003 # runner args - max_env_steps: 200000 + max_env_steps: 216000 warm_up_steps: 1000 rollout_batch_size: 4 - num_workers: 1 - max_buffer_size: 50000 - deque_size: 10 - eval_batch_size: 50 + max_buffer_size: 54000 + eval_batch_size: 10 # misc - log_interval: 2000 - save_interval: 0 + log_interval: 5400 + save_interval: 480000 num_checkpoints: 0 - eval_interval: 2000 + eval_interval: 5400 eval_save_best: True tensorboard: False diff --git a/examples/rl/data_analysis.ipynb b/examples/rl/data_analysis.ipynb index 9136d8ef8..cea91ba37 100644 --- a/examples/rl/data_analysis.ipynb +++ b/examples/rl/data_analysis.ipynb @@ -56,39 +56,55 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 32, "metadata": {}, "outputs": [], "source": [ - "seeds = [i for i in range(0,10)]\n", + "seeds = [i for i in range(0,5)]\n", "#seeds = [0]\n", "\n", "data_paths = {\n", - " \"PPO\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Longest_run/\",\n", - " # \"ppo_1\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Long_run/\", \n", - " # \"ppo_2\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Medium_run/\",\n", + " # \"PPO\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Longest_run/\",\n", + " #\"PPO\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Long_run/\", \n", + " # \"PPO\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Long_run2/\", \n", + " \"PPO\": \"/home/savvyfox/Projects/scg-exp/examples/rl/Results/exp_data/quadrotor_2D_attitude_ppo_data/\",\n", + " #\"PPO\": \"/home/savvyfox/Projects/scg-exp/examples/rl/Results/exp_data_T/quadrotor_2D_attitude_ppo_data/\",\n", + " #\"PPO\": \"/home/savvyfox/Projects/scg-exp/examples/rl/Results/exp_data_F/quadrotor_2D_attitude_ppo_data/\",\n", + " \"PPO3\": \"/home/savvyfox/Projects/scg-exp/examples/rl/Results/quadrotor_2D_attitude_ppo_data/PPO_ilqr_ref/\",\n", + " \"PPO4\": \"/home/savvyfox/Projects/scg-exp/examples/rl/Results/quadrotor_2D_attitude_ppo_data/PPO_ilqr_ref_woa/\",\n", + " # \"PPO\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Medium_run/\",\n", " # \"ppo_22\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Medium_run2/\",\n", " # \"ppo_3\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Short_run/\",\n", " # \"ppo_4\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_ppo_data/Shortest_run/\",\n", - " \"SAC\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Longest_run/\",\n", - " # \"sac_1\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Long_run/\", \n", - " # \"sac_2\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Medium_run/\",\n", + " # \"SAC\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Longest_run/\",\n", + " # \"SAC\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Long_run/\", \n", + " # \"SAC\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Long_run2/\", \n", + " # \"SAC\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Medium_run/\",\n", " # \"sac_22\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Medium_run2/\",\n", " # \"sac_3\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Short_run/\",\n", " # \"sac_4\": os.getcwd()+\"/Results/LSY_pc/quadrotor_2D_attitude_sac_data/Shortest_run/\",\n", "}\n", "\n", "colors = {\n", - " \"PPO\": \"orange\",\n", - " \"SAC\": \"green\",\n", - " \"GP MPC\": \"royalblue\",\n", - " \"iLQR\": \"gray\"\n", + " \"PPO\": \"tab:orange\",\n", + " \"PPO2\": \"tab:red\",\n", + " \"PPO3\": \"tab:olive\",\n", + " \"PPO4\": \"tab:cyan\",\n", + " \"SAC\": \"tab:green\",\n", + " \"GP MPC\": \"tab:blue\",\n", + " \"iLQR\": \"tab:gray\"\n", + "}\n", + "\n", + "legends = {\n", + " \"PPO\": \"PPO\",\n", + " \"PPO3\": \"PPO with ilqr ref\",\n", + " \"PPO4\": \"PPO with ilqr state ref\"\n", "}" ] }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 33, "metadata": {}, "outputs": [ { @@ -96,7 +112,8 @@ "output_type": "stream", "text": [ "PPO\n", - "SAC\n" + "PPO3\n", + "PPO4\n" ] } ], @@ -112,8 +129,8 @@ " # xk, x, ck, c = load_from_log_file(data_paths[method] + str(seed) + \"/logs/stat_eval/constraint_violation.log\")\n", " # perf_data[method].update({seed: {\"x\": x, \"y\": y, \"c\": c}})\n", " # perf_data[method].update({seed: {\"x\": x, \"y\": y, \"z\": z, \"c\": c}})\n", - " xk, x, yk, m = load_from_log_file(data_paths[method] + str(seed) + \"/logs/stat_eval/mse.log\")\n", - " xk, x, yk, n = load_from_log_file(data_paths[method] + str(seed) + \"/logs/stat_eval/mse_std.log\")\n", + " xk, x, yk, m = load_from_log_file(data_paths[method] + str(seed) + \"/logs/stat_eval/rmse.log\")\n", + " xk, x, yk, n = load_from_log_file(data_paths[method] + str(seed) + \"/logs/stat_eval/rmse_std.log\")\n", " # perf_data[method].update({\"x\": x, \"y\": y, \"z\": z, \"x1\": x1, \"y1\": y1, \"z1\": z1})\n", " perf_data[method].update({seed: {\"x\": x, \"y\": y, \"z\": z, \"m\": m, \"n\": n, \"l\": l}})" ] @@ -129,7 +146,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 34, "metadata": {}, "outputs": [ { @@ -137,7 +154,11 @@ "output_type": "stream", "text": [ "PPO\n", - "SAC\n" + "0.09238627995541378\n", + "PPO3\n", + "0.350353943509043\n", + "PPO4\n", + "0.17088204404413107\n" ] }, { @@ -146,13 +167,13 @@ "Text(0.5, 1.0, 'Task: Quadrotor 2D')" ] }, - "execution_count": 8, + "execution_count": 34, "metadata": {}, "output_type": "execute_result" }, { "data": { - "image/png": "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", + "image/png": "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", "text/plain": [ "
" ] @@ -166,7 +187,8 @@ "w = 1\n", "fig = plt.figure()\n", "last_iter = perf_data[\"PPO\"][0][\"x\"][-1]\n", - "for method in data_paths.keys():\n", + "dummy = [0.15, 0.12]\n", + "for t, method in enumerate(data_paths.keys()):\n", " print(method)\n", " temp = np.zeros((len(seeds), 6, perf_data[method][seeds[0]][\"x\"].shape[0]))\n", " for seed in seeds:\n", @@ -174,9 +196,10 @@ " temp[seed, 0, :] = perf_data[method][seed][\"x\"]\n", " temp[seed, 1, :] = perf_data[method][seed][\"y\"]\n", " temp[seed, 2, :] = perf_data[method][seed][\"z\"]\n", - " temp[seed, 3, :] = (perf_data[method][seed][\"m\"])**0.5\n", - " temp[seed, 4, :] = perf_data[method][seed][\"n\"]**0.5\n", + " temp[seed, 3, :] = perf_data[method][seed][\"m\"]\n", + " temp[seed, 4, :] = perf_data[method][seed][\"n\"]\n", " temp[seed, 5, :] = perf_data[method][seed][\"l\"]\n", + " j_max = 0\n", " for seed in seeds:\n", " for j,k in enumerate(temp[seed, 0, :]):\n", " if temp[seed, 5, j] < 540:\n", @@ -185,57 +208,52 @@ " temp[seed, 2, j] = np.nan\n", " temp[seed, 3, j] = np.nan\n", " temp[seed, 4, j] = np.nan\n", + " if j >= j_max:\n", + " j_max = j+1\n", " eval_data.update({method: temp})\n", " start_iter = last_iter - perf_data[method][seed][\"x\"][-1]\n", + " start_iter = 0\n", "\n", " # plotting performance\n", " # plt.plot(start_iter+temp[0,0,w-1:], moving_average(np.mean(temp[:,3,:], axis=0), w), label=method)\n", " # plt.fill_between(start_iter+temp[0,0,w-1:], \n", " # moving_average(np.mean(temp[:,3,:], axis=0)-np.mean(temp[:,4,:], axis=0), w), \n", " # moving_average(np.mean(temp[:,3,:], axis=0)+np.mean(temp[:,4,:], axis=0), w), alpha=0.25)\n", - " plt.plot(start_iter+temp[0,0,:], np.mean(temp[:,3,:], axis=0), color=colors[method], label=method)\n", + " plt.plot(start_iter+temp[0,0,:], np.mean(temp[:,3,:], axis=0), color=colors[method], label=legends[method])\n", " plt.fill_between(start_iter+temp[0,0,:], \n", - " np.mean(temp[:,3,:], axis=0)-np.mean(temp[:,4,:], axis=0), \n", - " np.mean(temp[:,3,:], axis=0)+np.mean(temp[:,4,:], axis=0), color=colors[method], alpha=0.25)\n", + " np.mean(temp[:,3,:]-temp[:,4,:], axis=0), \n", + " np.mean(temp[:,3,:]+temp[:,4,:], axis=0), color=colors[method], alpha=0.25)\n", + " print(np.mean(temp[:,3,j_max], axis=0))\n", + " # plt.axhline(xmin=0.0, xmax=dummy[t], y=np.array(temp[:,3,j_max]).mean(), linestyle='-.', color='lightgray')\n", "\n", " # plotting constraint violations\n", " # plt.plot(temp[0,0,:], np.mean(temp[:,3,:], axis=0), label=method)\n", "\n", - "gp_mpc_data = np.load(\"./Results/LSY_pc/GPMPC_rmse_200_mass_20_sample_10_epoch.npy\", allow_pickle=True).item()\n", - "start_iter = last_iter - gp_mpc_data['train_steps'][-1]\n", - "plt.plot(0*start_iter+gp_mpc_data['train_steps'], gp_mpc_data['mean'], color=colors[\"GP MPC\"], label='GP MPC')\n", - "plt.fill_between(0*start_iter+gp_mpc_data['train_steps'], \n", - " gp_mpc_data['mean']-gp_mpc_data['std'], \n", - " gp_mpc_data['mean']+gp_mpc_data['std'], color=colors[\"GP MPC\"], alpha=0.25)\n", + "# gp_mpc_data = np.load(\"./Results/LSY_pc/GPMPC_rmse_200_mass_20_sample_10_epoch.npy\", allow_pickle=True).item()\n", + "# start_iter = last_iter - gp_mpc_data['train_steps'][-1]\n", + "# plt.plot(0*start_iter+gp_mpc_data['train_steps'], gp_mpc_data['mean'], color=colors[\"GP MPC\"], label='GP MPC')\n", + "# plt.fill_between(0*start_iter+gp_mpc_data['train_steps'], \n", + "# gp_mpc_data['mean']-gp_mpc_data['std'], \n", + "# gp_mpc_data['mean']+gp_mpc_data['std'], color=colors[\"GP MPC\"], alpha=0.25)\n", "\n", "s = 1 # time std\n", "rmse_ilqr_mean = 0.026000000000000002\n", "rmse_ilqr_std = 0.001843908891458577\n", - "plt.axhline(xmin=0.0, xmax=0.95, y=rmse_ilqr_mean, linestyle='--', color=colors[\"iLQR\"], label='iLQR')\n", + "plt.axhline(xmin=0.0, xmax=1.0, y=rmse_ilqr_mean, linestyle='--', color=colors[\"iLQR\"], label='iLQR')\n", "plt.fill_between([0.0, last_iter], rmse_ilqr_mean-s*rmse_ilqr_std, rmse_ilqr_mean+s*rmse_ilqr_std, color=colors[\"iLQR\"], alpha=0.25)\n", "\n", - "# gp_05 = np.load(os.getcwd() + \"/gp_mpc_data/gp_mpc_M_0.5_cost.npy\", allow_pickle=True)\n", - "# gp_10 = np.load(os.getcwd() + \"/gp_mpc_data/gp_mpc_M_1.0_cost.npy\", allow_pickle=True)\n", - "# gp_30 = np.load(os.getcwd() + \"/gp_mpc_data/gp_mpc_M_3.0_cost.npy\", allow_pickle=True)\n", - "# plt.plot(gp_05.item()[\"mean\"][:,0], gp_05.item()[\"mean\"][:,1], label=\"GP-MPC (m=0.5)\")\n", - "# plt.fill_between(gp_05.item()[\"mean\"][:,0], gp_05.item()[\"mean\"][:,1]-gp_05.item()[\"std\"], gp_05.item()[\"mean\"][:,1]+gp_05.item()[\"std\"], alpha=0.25)\n", - "# plt.plot(gp_10.item()[\"mean\"][:,0], gp_10.item()[\"mean\"][:,1], label=\"GP-MPC (m=1.0)\")\n", - "# plt.fill_between(gp_10.item()[\"mean\"][:,0], gp_10.item()[\"mean\"][:,1]-gp_10.item()[\"std\"], gp_10.item()[\"mean\"][:,1]+gp_10.item()[\"std\"], alpha=0.25)\n", - "# plt.plot(gp_30.item()[\"mean\"][:,0], gp_30.item()[\"mean\"][:,1], label=\"GP-MPC (m=3.0)\")\n", - "# plt.fill_between(gp_30.item()[\"mean\"][:,0], gp_30.item()[\"mean\"][:,1]-gp_30.item()[\"std\"], gp_30.item()[\"mean\"][:,1]+gp_30.item()[\"std\"], alpha=0.25)\n", - "# gp_05 = np.load(os.getcwd() + \"/gp_mpc_data/gp_mpc_M_0.5_constraint_percentage.npy\", allow_pickle=True)\n", - "# gp_10 = np.load(os.getcwd() + \"/gp_mpc_data/gp_mpc_M_1.0_constraint_percentage.npy\", allow_pickle=True)\n", - "# gp_30 = np.load(os.getcwd() + \"/gp_mpc_data/gp_mpc_M_3.0_constraint_percentage.npy\", allow_pickle=True)\n", - "# plt.plot(gp_05.item()[\"mean\"][:,0], gp_05.item()[\"mean\"][:,1], label=\"GP-MPC (m=0.5)\")\n", - "# plt.plot(gp_10.item()[\"mean\"][:,0], gp_10.item()[\"mean\"][:,1], label=\"GP-MPC (m=1.0)\")\n", - "# plt.plot(gp_30.item()[\"mean\"][:,0], gp_30.item()[\"mean\"][:,1], label=\"GP-MPC (m=3.0)\")\n", "\n", + "# real experiment data\n", + "# plt.plot(last_iter, 0.086, color=colors['PPO'], marker='x')\n", + "# plt.plot(last_iter, 0.064, color=colors['SAC'], marker='x')\n", "\n", "plt.legend()\n", "# plt.ylim(-200,00)\n", - "plt.xscale(\"log\")\n", + "plt.xlim(0, 216000)\n", + "# plt.xscale(\"log\")\n", "# plt.gca().invert_xaxis()\n", - "plt.yscale(\"log\")\n", + "# plt.yscale(\"log\")\n", + "# plt.text(900, 0.3, \"Unssucessful evaluation runs\", bbox=dict(facecolor='red', alpha=0.25))\n", "plt.xlabel(\"Training steps\")\n", "plt.ylabel(\"RMSE\")\n", "plt.title(\"Task: Quadrotor 2D\")\n", @@ -244,31 +262,904 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": 42, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "PPO\n", + "SAC\n" + ] + } + ], + "source": [ + "metric = {}\n", + "noise_scale = [1,10,20,30,40,50,60,70,80,90,100,110,120,130,140,150,160,170,180,190,200]\n", + "for method in data_paths.keys():\n", + " print(method)\n", + " metric.update({method: {}})\n", + " for seed in seeds:\n", + " for ns in noise_scale:\n", + " temp = np.load(data_paths[method] + str(seed) +\"/metric_\"+str(ns)+\".npy\", allow_pickle=True).item()\n", + " if ns in metric[method].keys():\n", + " metric[method][ns]['rmse'].append(temp['rmse'])\n", + " metric[method][ns]['rmse_std'].append(temp['rmse_std'])\n", + " temp2 = True if temp['average_length'] == 540.0 else False\n", + " metric[method][ns]['success'].append(temp2)\n", + " else:\n", + " temp2 = True if temp['average_length'] == 540.0 else False\n", + " metric[method].update({ns: {'rmse': [temp['rmse']], \n", + " 'rmse_std': [temp['rmse_std']], \n", + " 'success': [temp2]}})" + ] + }, + { + "cell_type": "code", + "execution_count": 20, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "{'PPO': {1: {'rmse': [array([0.03954991, 0.02952318, 0.04092114, 0.02800149, 0.04400959,\n", + " 0.02662548, 0.02944364, 0.03904875, 0.02775426, 0.03511278]),\n", + " array([0.04070723, 0.03145395, 0.04028517, 0.02766346, 0.0415407 ,\n", + " 0.02562376, 0.02981484, 0.03994833, 0.03090729, 0.03735818]),\n", + " array([0.03145983, 0.01972989, 0.03287851, 0.01808824, 0.04164756,\n", + " 0.01953648, 0.01790794, 0.02994907, 0.01933651, 0.02548464]),\n", + " array([0.04154148, 0.03171375, 0.04197975, 0.03146355, 0.05187719,\n", + " 0.03221417, 0.03158112, 0.04101934, 0.03301357, 0.03627831]),\n", + " array([0.04409871, 0.03176296, 0.04428743, 0.02909585, 0.04595522,\n", + " 0.02921067, 0.03091882, 0.04329685, 0.03441138, 0.03782479])],\n", + " 'rmse_std': [0.006130261237096689,\n", + " 0.005736516148837012,\n", + " 0.007679949768696556,\n", + " 0.0063989610003052306,\n", + " 0.0064668992900339065]},\n", + " 10: {'rmse': [array([0.16413027, 0.15811217, 0.17252589, 0.17375992, 0.16505922,\n", + " 0.13834003, 0.16334804, 0.16510907, 0.12438691, 0.14719491]),\n", + " array([0.16240275, 0.12344306, 0.14968762, 0.16054998, 0.17956325,\n", + " 0.14173498, 0.14554519, 0.15355354, 0.12473493, 0.14989054]),\n", + " array([0.21085396, 0.17584419, 0.16687748, 0.2220897 , 0.23756314,\n", + " 0.19383375, 0.2196915 , 0.18821803, 0.20925829, 0.22302747]),\n", + " array([0.28413222, 0.28507308, 0.27212589, 0.32562612, 0.30504042,\n", + " 0.27413011, 0.26021165, 0.27089405, 0.26612339, 0.25141092]),\n", + " array([0.20872871, 0.22504148, 0.19551697, 0.23269224, 0.22110672,\n", + " 0.2044967 , 0.21535611, 0.18881279, 0.20828767, 0.20617963])],\n", + " 'rmse_std': [0.01500864103783961,\n", + " 0.016048966329323896,\n", + " 0.021574530440060535,\n", + " 0.020807907121911943,\n", + " 0.01263902449723195]},\n", + " 20: {'rmse': [array([0.4419072 , 0.45636889, 0.46368068, 0.50225035, 0.46132054,\n", + " 0.41352429, 0.4857885 , 0.49414452, 0.34899564, 0.40564418]),\n", + " array([0.50365474, 0.39819431, 0.42614543, 0.49690961, 0.52565847,\n", + " 0.4566693 , 0.46090862, 0.45927813, 0.41694389, 0.47661259]),\n", + " array([0.86898108, 0.70668355, 0.69629308, 0.95553917, 0.96557362,\n", + " 0.79718888, 0.92525775, 0.82136398, 0.80401174, 1.03937223]),\n", + " array([0.55828278, 0.59067868, 0.7224181 , 0.80341888, 0.63456679,\n", + " 0.78016061, 0.76093829, 0.50010175, 0.79406404, 0.784785 ]),\n", + " array([0.42148194, 0.46813303, 0.38366625, 0.47532882, 0.44853407,\n", + " 0.42703595, 0.44056467, 0.37071424, 0.42967857, 0.416128 ])],\n", + " 'rmse_std': [0.044509840381252795,\n", + " 0.038266718102740134,\n", + " 0.10752988326483065,\n", + " 0.1063725924810573,\n", + " 0.03140756693416255]},\n", + " 30: {'rmse': [array([0.45716743, 0.64354722, 0.62273107, 0.82015201, 0.7073089 ,\n", + " 0.44988286, 0.76155342, 0.71739206, 0.78476455, 0.74182997]),\n", + " array([0.73530782, 0.76132063, 0.73965977, 0.65037272, 0.74902115,\n", + " 0.67424986, 0.66578888, 0.69922094, 0.68152677, 0.70728499]),\n", + " array([0.86368737, 0.68463817, 0.88249606, 0.70017203, 1.71906891,\n", + " 0.8186743 , 1.40357342, 0.66857713, 0.66938706, 0.95420159]),\n", + " array([0.55083453, 0.4087256 , 0.41411023, 0.39177911, 0.43317632,\n", + " 0.39616893, 0.37665269, 0.40144564, 0.42206121, 0.39922709]),\n", + " array([0.60404637, 0.56674895, 0.58578733, 0.53662805, 0.60508204,\n", + " 0.60202229, 0.59442244, 0.61210209, 0.60873293, 0.60812025])],\n", + " 'rmse_std': [0.12230102911878218,\n", + " 0.03642479337538764,\n", + " 0.3339765372850518,\n", + " 0.04633903330760064,\n", + " 0.022599598964730603]},\n", + " 40: {'rmse': [array([0.74872627, 0.51388869, 0.4280038 , 0.709051 , 1.01529119,\n", + " 0.44235277, 0.87357365, 0.43311487, 0.77571949, 0.4693808 ]),\n", + " array([0.78827461, 0.53692953, 0.85807506, 0.50111579, 0.71780413,\n", + " 0.39725018, 0.80121659, 0.43593055, 0.8089775 , 0.837322 ]),\n", + " array([0.70775352, 0.63945735, 0.69291229, 0.64862135, 0.65009855,\n", + " 0.7126763 , 0.63807956, 0.73332609, 0.72756041, 0.82183005]),\n", + " array([0.45790955, 0.46941622, 0.37220685, 0.34149099, 0.36838096,\n", + " 0.41374366, 0.38891572, 0.39296751, 0.39262201, 0.40411986]),\n", + " array([0.61363326, 0.51316917, 0.6594003 , 0.59635675, 0.64553788,\n", + " 0.43464952, 0.54058833, 0.5757462 , 0.76444318, 0.66188532])],\n", + " 'rmse_std': [0.2005553070379508,\n", + " 0.17075036630548698,\n", + " 0.054347619947270415,\n", + " 0.03714828840433537,\n", + " 0.0869873702737044]},\n", + " 50: {'rmse': [array([0.73407984, 0.74423609, 0.49132412, 0.88161766, 0.48089967,\n", + " 0.67614039, 0.46831542, 0.49457136, 0.45589698, 0.62367405]),\n", + " array([0.44023209, 0.5166185 , 0.50514634, 0.49983241, 0.5033198 ,\n", + " 0.48938937, 0.3756381 , 0.39093487, 0.52474055, 0.43228864]),\n", + " array([0.681448 , 0.5984231 , 0.66422019, 0.656128 , 0.62407231,\n", + " 0.74631215, 0.64613271, 0.74880951, 0.5779126 , 0.77190205]),\n", + " array([0.43432474, 0.41738711, 0.3843027 , 0.39526353, 0.43574387,\n", + " 0.37644452, 0.43239446, 0.41200164, 0.45209087, 0.36712145]),\n", + " array([0.7295472 , 0.60075156, 0.51784877, 0.63635161, 0.69994194,\n", + " 0.5540772 , 0.65683448, 0.60328428, 0.42138935, 0.48304536])],\n", + " 'rmse_std': [0.14121161596069243,\n", + " 0.05118316424509169,\n", + " 0.062477318030184706,\n", + " 0.02724558331711334,\n", + " 0.09210439140305404]},\n", + " 60: {'rmse': [array([0.64491463, 0.4440219 , 0.44394628, 0.41506794, 0.50429917,\n", + " 0.5077751 , 0.56438629, 0.36574319, 0.45264382, 0.48935683]),\n", + " array([0.3945777 , 0.4472289 , 0.38140511, 0.39584745, 0.45582038,\n", + " 0.43659716, 0.41132724, 0.34367187, 0.47247054, 0.53605238]),\n", + " array([0.68217852, 0.60010585, 0.6972248 , 0.70385317, 0.69870832,\n", + " 0.79131209, 0.73543981, 0.66334998, 0.67270994, 0.73961799]),\n", + " array([0.43549299, 0.44567782, 0.48763791, 0.41615017, 0.41225022,\n", + " 0.46330876, 0.36535917, 0.34904425, 0.40876613, 0.47163887]),\n", + " array([0.78090514, 0.69191633, 0.53979657, 0.6669182 , 0.66344453,\n", + " 0.46408063, 0.77369437, 0.53700747, 0.67205343, 0.54702644])],\n", + " 'rmse_std': [0.07501825591101613,\n", + " 0.05155503208258913,\n", + " 0.048526357830558454,\n", + " 0.04234596663863948,\n", + " 0.1012750818915742]},\n", + " 70: {'rmse': [array([0.63636483, 0.38249512, 0.48038912, 0.42932279, 0.46019044,\n", + " 0.47733961, 0.43977732, 0.51202303, 0.50495255, 0.68193832]),\n", + " array([0.3757637 , 0.40974266, 0.34428525, 0.36802524, 0.41040109,\n", + " 0.41077194, 0.52359234, 0.38795774, 0.35563344, 0.50748999]),\n", + " array([0.69337764, 0.69379771, 0.59937641, 0.68255059, 0.65890741,\n", + " 0.72371696, 0.67534831, 0.69848969, 0.11380945, 0.62026499]),\n", + " array([0.42052613, 0.41156892, 0.55879811, 0.45439523, 0.47805472,\n", + " 0.41730942, 0.44395578, 0.42077983, 0.41744691, 0.31566702]),\n", + " array([0.60168814, 0.59239963, 0.72627235, 0.46337921, 0.5009498 ,\n", + " 0.54601978, 0.78279967, 0.56446143, 0.5966506 , 0.70300596])],\n", + " 'rmse_std': [0.08762192651136472,\n", + " 0.05753115962235753,\n", + " 0.17109336488112709,\n", + " 0.05783164615876285,\n", + " 0.09596506647836854]},\n", + " 80: {'rmse': [array([0.56565023, 0.4789668 , 0.59851935, 0.45373701, 0.44777974,\n", + " 0.58634255, 0.43868896, 0.60673974, 0.3786683 , 0.52902882]),\n", + " array([0.3690116 , 0.40086166, 0.43720708, 0.40182652, 0.3868579 ,\n", + " 0.38213621, 0.41656804, 0.34501908, 0.39530568, 0.35087691]),\n", + " array([0.72918427, 0.69446191, 0.60403243, 0.73083143, 0.75796657,\n", + " 0.09519283, 0.08436839, 0.71425979, 0.12505715, 0.12097274]),\n", + " array([0.45129333, 0.43525485, 0.37981972, 0.40896819, 0.43201798,\n", + " 0.37836192, 0.38634594, 0.48404725, 0.47031947, 0.50290126]),\n", + " array([0.59774107, 0.5185945 , 0.77324759, 0.51468932, 0.65270713,\n", + " 0.61905795, 0.71108464, 0.38492408, 0.59704786, 0.65143196])],\n", + " 'rmse_std': [0.07535880282928208,\n", + " 0.026955431577383168,\n", + " 0.29596485956014146,\n", + " 0.042181739845464694,\n", + " 0.10405533126514528]},\n", + " 90: {'rmse': [array([0.56760671, 0.46453023, 0.59453313, 0.5064146 , 0.49365335,\n", + " 0.50866828, 0.44225 , 0.57978095, 0.53327846, 0.43585626]),\n", + " array([0.3694675 , 0.38131634, 0.43261323, 0.38800305, 0.40181652,\n", + " 0.39102165, 0.39575603, 0.44656042, 0.39313819, 0.4258435 ]),\n", + " array([0.11490757, 0.15885547, 0.08701126, 0.07800613, 0.14601306,\n", + " 0.07717611, 0.60661204, 0.09087247, 0.02400453, 0.13035429]),\n", + " array([0.4702941 , 0.40842666, 0.42352826, 0.45564662, 0.42859059,\n", + " 0.4457893 , 0.47549454, 0.46437007, 0.4140222 , 0.45577455]),\n", + " array([0.63472896, 0.70943549, 0.78759712, 0.57281357, 0.77659884,\n", + " 0.52743078, 0.7535397 , 0.72581908, 0.62637874, 0.7401388 ])],\n", + " 'rmse_std': [0.05314295834362226,\n", + " 0.023256002590387324,\n", + " 0.15620888652630827,\n", + " 0.022794753621666004,\n", + " 0.08502544372381218]},\n", + " 100: {'rmse': [array([0.57446748, 0.45560066, 0.4297663 , 0.6286068 , 0.49910753,\n", + " 0.48273396, 0.41141275, 0.47506466, 0.49982776, 0.44110922]),\n", + " array([0.38708817, 0.39716483, 0.5787624 , 0.46918746, 0.43977465,\n", + " 0.38277159, 0.41665808, 0.44441552, 0.5079856 , 0.46105881]),\n", + " array([0.11132125, 0.17873956, 0.11593397, 0.05746863, 0.1560173 ,\n", + " 0.04242785, 0.64893869, 0.09063232, 0.06933018, 0.03386612]),\n", + " array([0.47847737, 0.4554602 , 0.38042581, 0.42245538, 0.40162354,\n", + " 0.63778638, 0.49258709, 0.51995678, 0.41175087, 0.49240339]),\n", + " array([0.67042248, 0.5515114 , 0.69559034, 0.50574265, 0.87918787,\n", + " 0.794219 , 0.59031254, 0.95675291, 0.81644806, 0.5540509 ])],\n", + " 'rmse_std': [0.06338701676333387,\n", + " 0.057381339624842376,\n", + " 0.1720782894553033,\n", + " 0.07091588981932696,\n", + " 0.14644418256883446]},\n", + " 110: {'rmse': [array([0.57161794, 0.47726254, 0.50634152, 0.64903104, 0.48467362,\n", + " 0.47464772, 0.48514406, 0.53087041, 0.42353826, 0.54851066]),\n", + " array([0.36805125, 0.38991624, 0.57686548, 0.38691614, 0.44781162,\n", + " 0.39901003, 0.40848926, 0.61537554, 0.47471065, 0.43099503]),\n", + " array([0.10881868, 0.10025461, 0.21635583, 0.07256814, 0.58111356,\n", + " 0.03287557, 0.71153972, 0.08943711, 0.10419337, 0.09462352]),\n", + " array([0.47650235, 0.5306273 , 0.0773954 , 0.46989621, 0.37959012,\n", + " 0.43848536, 0.48925906, 0.41256793, 0.45878882, 0.42435683]),\n", + " array([0.7066126 , 0.65083839, 0.81970074, 0.57696332, 0.86304523,\n", + " 0.70495022, 0.75835211, 0.85690697, 0.80236913, 0.54887069])],\n", + " 'rmse_std': [0.05987335374612864,\n", + " 0.07940309384331996,\n", + " 0.22380311883554121,\n", + " 0.11977806283064474,\n", + " 0.10561717241032428]},\n", + " 120: {'rmse': [array([0.58183943, 0.50561568, 0.54543446, 0.43603097, 0.59439157,\n", + " 0.48048602, 0.47136941, 0.41013123, 0.61618388, 0.60364239]),\n", + " array([0.3730246 , 0.39640977, 0.45696544, 0.45945259, 0.35608102,\n", + " 0.59137298, 0.39064278, 0.45505879, 0.44817069, 0.35253502]),\n", + " array([0.10546194, 0.11647078, 0.22705725, 0.03977198, 0.65934326,\n", + " 0.07519135, 0.69345919, 0.10217798, 0.19088411, 0.03282592]),\n", + " array([0.52155975, 0.59365457, 0.07075362, 0.50893641, 0.41861353,\n", + " 0.41122364, 0.46414627, 0.45944349, 0.50462189, 0.42791529]),\n", + " array([0.74743632, 0.86961731, 0.6398568 , 0.81693755, 0.69601596,\n", + " 0.74068047, 0.78911122, 0.563852 , 0.8104074 , 0.8532123 ])],\n", + " 'rmse_std': [0.07021683257111276,\n", + " 0.06777987843904215,\n", + " 0.23326099310381576,\n", + " 0.1333749651529687,\n", + " 0.09183527209145864]},\n", + " 130: {'rmse': [array([0.58428915, 0.47689809, 0.53686846, 0.61725344, 0.44527193,\n", + " 0.46982405, 0.50097594, 0.57150314, 0.80337978, 0.41284686]),\n", + " array([0.3737616 , 0.39395278, 0.42124432, 0.47182387, 0.70350694,\n", + " 0.61017942, 0.50084039, 0.44654675, 0.45374785, 0.448765 ]),\n", + " array([0.10588795, 0.11526076, 0.23688171, 0.04028951, 0.19216986,\n", + " 0.10645755, 0.07230313, 0.1103428 , 0.10855791, 0.19119178]),\n", + " array([0.50279917, 0.64521147, 0.08538259, 0.49793536, 0.5249937 ,\n", + " 0.5583629 , 0.4365541 , 0.51081033, 0.40743423, 0.54404467]),\n", + " array([0.7844074 , 0.68897943, 0.92294839, 0.6655313 , 0.68408855,\n", + " 0.54817551, 0.85474552, 0.73519926, 0.83926833, 0.50705994])],\n", + " 'rmse_std': [0.10669348010770609,\n", + " 0.09605763480289807,\n", + " 0.057067072640825535,\n", + " 0.14264676100415852,\n", + " 0.1256750189590696]},\n", + " 140: {'rmse': [array([0.57965017, 0.51518198, 0.53446955, 0.59732573, 0.49816613,\n", + " 0.42752133, 0.51588298, 0.49633817, 0.46986668, 0.48584539]),\n", + " array([0.40585849, 0.38567176, 0.43537661, 0.47203526, 0.69773935,\n", + " 0.1962198 , 0.40675985, 0.3827441 , 0.51000353, 0.42898605]),\n", + " array([0.1126913 , 0.11379988, 0.34907478, 0.06771059, 0.07580797,\n", + " 0.0940617 , 0.04268514, 0.04347448, 0.34432499, 0.27733218]),\n", + " array([0.53913664, 0.70631565, 0.06475761, 0.66538695, 0.45142909,\n", + " 0.47824932, 0.41332333, 0.57764116, 0.3500496 , 0.51745094]),\n", + " array([0.83074412, 0.7867324 , 0.96013274, 0.69077566, 0.64665006,\n", + " 0.55857056, 0.74385607, 0.85791568, 0.96046011, 0.58344894])],\n", + " 'rmse_std': [0.04734944217854239,\n", + " 0.11824139144950739,\n", + " 0.11598886083967386,\n", + " 0.17160058959620425,\n", + " 0.13607055053019504]},\n", + " 150: {'rmse': [array([0.56613411, 0.49036259, 0.51402738, 0.65151849, 0.50167998,\n", + " 0.6037896 , 0.56923768, 0.46704458, 0.44555736, 0.48847063]),\n", + " array([0.40038265, 0.38453501, 0.42709841, 0.51307049, 0.5397541 ,\n", + " 0.45563831, 0.52594172, 0.47105669, 0.40594602, 0.45287228]),\n", + " array([0.11023922, 0.08705394, 0.07709309, 0.12260061, 0.08910233,\n", + " 0.11374472, 0.14235201, 0.15044418, 0.09398808, 0.08315932]),\n", + " array([0.1452615 , 0.47780233, 0.44708189, 0.45198686, 0.53142754,\n", + " 0.51108295, 0.53154922, 0.46825025, 0.43425082, 0.05864995]),\n", + " array([0.87506157, 0.78356748, 0.80102 , 0.67374651, 0.75282626,\n", + " 0.68353175, 0.80933507, 0.70549595, 0.95475814, 0.81561577])],\n", + " 'rmse_std': [0.06205106670486983,\n", + " 0.05187960618479478,\n", + " 0.02405577268705832,\n", + " 0.15646223273284568,\n", + " 0.08291191392933239]},\n", + " 160: {'rmse': [array([0.57711365, 0.52172606, 0.56797994, 0.45768358, 0.6509179 ,\n", + " 0.60600756, 0.85321874, 0.49547107, 0.48867265, 0.4885401 ]),\n", + " array([0.39221221, 0.38733033, 0.43087668, 0.55878612, 0.38033164,\n", + " 0.5950013 , 0.43203953, 0.40130906, 0.42297675, 0.58482863]),\n", + " array([0.1132335 , 0.10372253, 0.02254416, 0.04798749, 0.0533905 ,\n", + " 0.06670664, 0.09602971, 0.12445782, 0.06906142, 0.15303892]),\n", + " array([0.12602305, 0.48710635, 0.43951639, 0.07675998, 0.49115135,\n", + " 0.46751024, 0.54970987, 0.69122664, 0.47054959, 0.08526364]),\n", + " array([0.91802086, 0.81460766, 0.778633 , 0.79139277, 0.77729991,\n", + " 0.82992897, 0.88743005, 0.75051421, 0.89962022, 0.91943871])],\n", + " 'rmse_std': [0.11038848730169559,\n", + " 0.0813720959183366,\n", + " 0.03783389153367752,\n", + " 0.2028541973911697,\n", + " 0.06075036465214565]},\n", + " 170: {'rmse': [array([0.58301161, 0.48944584, 0.57463298, 0.46799614, 0.68058004,\n", + " 0.62605664, 0.56960304, 0.55828737, 0.5757421 , 0.59697199]),\n", + " array([0.41943416, 0.41516104, 0.43073832, 0.60098236, 0.51889096,\n", + " 0.39859549, 0.49123364, 0.39368281, 0.41509644, 0.4254096 ]),\n", + " array([0.10268297, 0.08633788, 0.11946848, 0.09008643, 0.09789426,\n", + " 0.1850894 , 0.11678534, 0.13106055, 0.09786801, 0.04717965]),\n", + " array([0.13291877, 0.45995591, 0.48349198, 0.08297724, 0.52453778,\n", + " 0.50256369, 0.52066259, 0.50283721, 0.5080131 , 0.08958297]),\n", + " array([0.96029986, 0.82854386, 0.75672193, 0.84803263, 0.70894343,\n", + " 0.7463173 , 0.85735049, 0.76241818, 1.06448999, 0.75202643])],\n", + " 'rmse_std': [0.05770855299965232,\n", + " 0.06276095270076928,\n", + " 0.033767600042758535,\n", + " 0.18381699704435026,\n", + " 0.1052098984673939]},\n", + " 180: {'rmse': [array([0.58271255, 0.70796824, 0.96789853, 0.43796615, 0.88902406,\n", + " 0.44082966, 0.5854809 , 0.58571176, 0.48540952, 0.54557537]),\n", + " array([0.40738108, 0.40478434, 0.38366719, 0.46291075, 0.41214482,\n", + " 0.42469484, 0.40153215, 0.46686777, 0.31689936, 0.45375759]),\n", + " array([0.10296797, 0.08598738, 0.0999425 , 0.11068457, 0.07164375,\n", + " 0.1866962 , 0.15713731, 0.08426571, 0.15025289, 0.09700723]),\n", + " array([0.17325952, 0.46166507, 0.4508975 , 0.08394034, 0.45023229,\n", + " 0.48183371, 0.49509066, 0.48837027, 0.4555754 , 0.07806305]),\n", + " array([1.00056695, 0.86676032, 0.74004575, 0.86470641, 0.8177055 ,\n", + " 1.02625583, 0.85469739, 0.78241068, 0.87003295, 0.90986098])],\n", + " 'rmse_std': [0.17138075759807297,\n", + " 0.041851732347800694,\n", + " 0.03540826471228237,\n", + " 0.166126485401652,\n", + " 0.08397066507744241]},\n", + " 190: {'rmse': [array([0.5766221 , 0.54994539, 0.25546188, 0.4621576 , 0.77459124,\n", + " 0.70736916, 0.59475011, 0.50049229, 0.59756194, 0.60643452]),\n", + " array([0.43230278, 0.43253241, 0.41085863, 0.46734788, 0.41251581,\n", + " 0.40923957, 0.41530777, 0.45133614, 0.36598605, 0.46020259]),\n", + " array([0.11095497, 0.07571583, 0.07232248, 0.02342404, 0.0406753 ,\n", + " 0.03134111, 0.13959115, 0.10369566, 0.10212067, 0.21861317]),\n", + " array([0.26501058, 0.54068459, 0.47918112, 1.01123752, 0.48970324,\n", + " 0.48895787, 0.20772061, 0.51920112, 0.46922961, 0.16700569]),\n", + " array([1.05800705, 0.88290399, 0.66779595, 0.85579242, 0.79103913,\n", + " 0.97535784, 0.83397782, 0.7719746 , 0.88030377, 0.9165602 ])],\n", + " 'rmse_std': [0.13368336416802243,\n", + " 0.02830408821855785,\n", + " 0.0552836753889023,\n", + " 0.22437002174552684,\n", + " 0.10328493770490303]},\n", + " 200: {'rmse': [array([0.56411521, 0.5804466 , 0.2685552 , 0.49007517, 0.75753386,\n", + " 0.88197982, 0.57611746, 0.52343361, 0.6327559 , 0.58528404]),\n", + " array([0.41467392, 0.45607198, 0.42199044, 0.45881674, 0.41116012,\n", + " 0.43769518, 0.50761289, 0.42830976, 0.33502091, 0.46529506]),\n", + " array([0.11107638, 0.07482206, 0.07842699, 0.13408251, 0.11241489,\n", + " 0.04674113, 0.13276488, 0.11311258, 0.10364231, 0.12221046]),\n", + " array([0.54144885, 0.12398471, 0.42322921, 0.10107834, 0.50479573,\n", + " 0.44955716, 0.50694684, 0.56076849, 0.8476639 , 0.08920608]),\n", + " array([1.09588862, 1.00340314, 0.82843924, 0.94642112, 0.81703062,\n", + " 0.78037283, 0.67321576, 0.73496447, 0.68803247, 0.57887893])],\n", + " 'rmse_std': [0.15287554233926628,\n", + " 0.04287474510693298,\n", + " 0.026533934270270617,\n", + " 0.23056310177070918,\n", + " 0.15212846396227367]}},\n", + " 'SAC': {1: {'rmse': [array([0.06315667, 0.05295258, 0.06084087, 0.05050985, 0.06358712,\n", + " 0.04775949, 0.05263644, 0.06282192, 0.0557945 , 0.05647834]),\n", + " array([0.05451718, 0.04283696, 0.05296381, 0.04067387, 0.05560048,\n", + " 0.03835898, 0.04263602, 0.05363344, 0.04562727, 0.04714812]),\n", + " array([0.06006862, 0.04849378, 0.05783869, 0.04687529, 0.0603008 ,\n", + " 0.04415727, 0.04844441, 0.06022592, 0.05132593, 0.05241107]),\n", + " array([0.05646731, 0.04676188, 0.05504362, 0.04446138, 0.05735333,\n", + " 0.04186813, 0.04654686, 0.05565081, 0.04892695, 0.05043421]),\n", + " array([0.05700006, 0.04639161, 0.05565491, 0.04461301, 0.05831832,\n", + " 0.04197521, 0.0460977 , 0.05644371, 0.04885052, 0.05046395])],\n", + " 'rmse_std': [0.005416638719644143,\n", + " 0.0060118015259800865,\n", + " 0.0058207101412428705,\n", + " 0.005220969784677572,\n", + " 0.005581415071703072]},\n", + " 10: {'rmse': [array([0.06997416, 0.06578056, 0.06502417, 0.06041652, 0.07111887,\n", + " 0.05431562, 0.05829907, 0.06746957, 0.06929869, 0.06673383]),\n", + " array([0.05800278, 0.05519576, 0.05639418, 0.04954587, 0.0648793 ,\n", + " 0.04555343, 0.04724663, 0.05539068, 0.06157276, 0.05726311]),\n", + " array([0.07414747, 0.06819749, 0.07161782, 0.06924562, 0.07447995,\n", + " 0.05658975, 0.06137438, 0.07439363, 0.07319077, 0.07084184]),\n", + " array([0.05800976, 0.05232542, 0.0543799 , 0.04669072, 0.05962749,\n", + " 0.04232532, 0.04768056, 0.05545877, 0.05767769, 0.05688031]),\n", + " array([0.06109266, 0.05525576, 0.05914062, 0.05333348, 0.06478089,\n", + " 0.04717067, 0.04996403, 0.06049697, 0.06125375, 0.05988103])],\n", + " 'rmse_std': [0.00519804671140716,\n", + " 0.005797116557493896,\n", + " 0.005697635737566897,\n", + " 0.005443385941447828,\n", + " 0.005315471109624291]},\n", + " 20: {'rmse': [array([0.10344469, 0.10967973, 0.09064373, 0.09658736, 0.09641722,\n", + " 0.08131003, 0.08308592, 0.09328206, 0.10463112, 0.09195149]),\n", + " array([0.08245033, 0.11616201, 0.09340439, 0.10016183, 0.13176869,\n", + " 0.09417959, 0.08133937, 0.07898064, 0.13491636, 0.09258414]),\n", + " array([0.14265412, 0.14346134, 0.14232737, 0.1509492 , 0.1458269 ,\n", + " 0.12584714, 0.13352154, 0.14543616, 0.1447259 , 0.14641757]),\n", + " array([0.07498991, 0.07420986, 0.07042834, 0.07147774, 0.07702778,\n", + " 0.05651634, 0.06630763, 0.0746852 , 0.08391904, 0.07955371]),\n", + " array([0.08239618, 0.08347469, 0.08331594, 0.09194278, 0.09614227,\n", + " 0.07083178, 0.07517607, 0.07525617, 0.09152483, 0.0951461 ])],\n", + " 'rmse_std': [0.008628843771462969,\n", + " 0.019278222531989873,\n", + " 0.006847039969655899,\n", + " 0.007155519098670522,\n", + " 0.0084835397417688]},\n", + " 30: {'rmse': [array([0.17010253, 0.20028456, 0.13739687, 0.15740044, 0.15631546,\n", + " 0.11503564, 0.12952918, 0.14083621, 0.15873373, 0.13040977]),\n", + " array([0.1672622 , 0.3067534 , 0.1694008 , 0.19313836, 0.2700321 ,\n", + " 0.15674771, 0.15930785, 0.14547968, 0.24526295, 0.15796038]),\n", + " array([0.23604722, 0.25560925, 0.23868266, 0.2640859 , 0.24543101,\n", + " 0.2298194 , 0.23726828, 0.25800675, 0.24026595, 0.25459696]),\n", + " array([0.10785606, 0.11096038, 0.10804595, 0.11625624, 0.11030279,\n", + " 0.08776481, 0.10302607, 0.11209994, 0.1250473 , 0.11715819]),\n", + " array([0.14067485, 0.14167885, 0.14622006, 0.16291074, 0.16276173,\n", + " 0.13796378, 0.1355025 , 0.12100559, 0.14780549, 0.1662558 ])],\n", + " 'rmse_std': [0.02317361888000187,\n", + " 0.053468658467345116,\n", + " 0.01077665418284039,\n", + " 0.009345906866054202,\n", + " 0.01351403084463997]},\n", + " 40: {'rmse': [array([0.25080893, 0.34817622, 0.20868181, 0.23343315, 0.30216961,\n", + " 0.17092332, 0.18848591, 0.2115797 , 0.24952177, 0.17717096]),\n", + " array([0.39017825, 0.710558 , 0.3086599 , 0.41399396, 0.51181618,\n", + " 0.23332341, 0.30094833, 0.3146481 , 0.36019517, 0.27404246]),\n", + " array([0.34309769, 0.38706341, 0.34334751, 0.40213614, 0.36690314,\n", + " 0.3594399 , 0.34271205, 0.38880013, 0.36374285, 0.36387223]),\n", + " array([0.1534625 , 0.15966953, 0.16176616, 0.17802816, 0.16226011,\n", + " 0.1350038 , 0.15812278, 0.16307541, 0.18132403, 0.16634176]),\n", + " array([0.21532544, 0.22050239, 0.22741688, 0.25563807, 0.24154773,\n", + " 0.22363232, 0.21590063, 0.20445992, 0.23963908, 0.25717646])],\n", + " 'rmse_std': [0.053507401475905846,\n", + " 0.132895546500146,\n", + " 0.019755156239319074,\n", + " 0.012134693098858906,\n", + " 0.016810216923345386]},\n", + " 50: {'rmse': [array([0.4490343 , 0.55584405, 0.28542788, 0.39294609, 0.55052508,\n", + " 0.30037014, 0.29598032, 0.37881774, 0.43240011, 0.25163603]),\n", + " array([0.80047064, 0.79017972, 0.82041295, 0.39486314, 0.65489532,\n", + " 0.72087501, 0.77902537, 0.67277976, 0.54172199, 0.66155778]),\n", + " array([0.45138223, 0.53848138, 0.50324529, 0.61746414, 0.5005206 ,\n", + " 0.49216937, 0.43454092, 0.53964617, 0.51876175, 0.47051738]),\n", + " array([0.20959202, 0.21895025, 0.22281763, 0.25038487, 0.22858093,\n", + " 0.1930503 , 0.22681552, 0.22300266, 0.24906651, 0.22683751]),\n", + " array([0.30425285, 0.32379512, 0.34415413, 0.35229326, 0.34056481,\n", + " 0.328119 , 0.31259966, 0.30896151, 0.34775233, 0.36896239])],\n", + " 'rmse_std': [0.1027800055144525,\n", + " 0.1261571932173699,\n", + " 0.04934278986848856,\n", + " 0.015957893390517515,\n", + " 0.019983891331671614]},\n", + " 60: {'rmse': [array([0.74051234, 0.73434477, 0.64111667, 0.35146255, 0.88559068,\n", + " 0.38249624, 0.51162186, 0.32233723, 0.68211964, 0.38428131]),\n", + " array([0.81863729, 0.92780796, 0.85038957, 0.71482982, 0.66876009,\n", + " 0.87992675, 0.67898596, 0.71864504, 0.69030458, 0.46793892]),\n", + " array([0.5895988 , 0.70916061, 0.76948699, 0.72886467, 0.64094118,\n", + " 0.68875439, 0.61039836, 0.54739137, 0.92095001, 0.59364855]),\n", + " array([0.27237725, 0.28525389, 0.28440103, 0.32853347, 0.30299996,\n", + " 0.25666914, 0.30115682, 0.288763 , 0.32156733, 0.29273932]),\n", + " array([0.42956715, 0.45311856, 0.50209131, 0.48807387, 0.45467209,\n", + " 0.43923815, 0.43432193, 0.44310846, 0.46023155, 0.51789879])],\n", + " 'rmse_std': [0.18842797173392992,\n", + " 0.12632060371334977,\n", + " 0.10438557399503663,\n", + " 0.020348110992917647,\n", + " 0.028705328682343812]},\n", + " 70: {'rmse': [array([0.79225211, 0.75981125, 0.64478162, 0.74918806, 0.7416423 ,\n", + " 0.85306896, 0.69019976, 0.75236233, 0.81630533, 0.6282316 ]),\n", + " array([0.71477137, 0.85027169, 0.67453357, 0.64733958, 0.78555241,\n", + " 0.73726481, 0.77120399, 0.90323995, 0.74758521, 0.80655418]),\n", + " array([0.84620693, 0.84829733, 0.70145626, 0.89993533, 0.82687641,\n", + " 0.88226539, 0.83458572, 0.98161842, 0.63226385, 0.81145089]),\n", + " array([0.34077288, 0.35496017, 0.34359219, 0.41240535, 0.37914275,\n", + " 0.3205413 , 0.37701413, 0.35990786, 0.39018966, 0.36248158]),\n", + " array([0.64985078, 0.62895895, 0.64682844, 0.67996727, 0.60208185,\n", + " 0.52911598, 0.60489903, 0.60056238, 0.58733243, 0.60977738])],\n", + " 'rmse_std': [0.06777245769037668,\n", + " 0.07360646287419141,\n", + " 0.09331846108345182,\n", + " 0.025244705182953887,\n", + " 0.03908723951337653]},\n", + " 80: {'rmse': [array([0.8258607 , 0.72458821, 0.67006355, 0.84173852, 0.53883874,\n", + " 0.85033577, 0.48694118, 0.74283426, 0.73568859, 0.83398912]),\n", + " array([0.7250907 , 0.81476099, 0.79172896, 0.78079336, 0.70941994,\n", + " 0.68702168, 0.69366992, 0.65737753, 0.77790759, 0.93293371]),\n", + " array([0.90039635, 0.84553955, 0.95067367, 0.9585539 , 1.02894594,\n", + " 0.962073 , 0.98854837, 0.86870018, 0.89579015, 0.88246058]),\n", + " array([0.41409439, 0.42759603, 0.40186382, 0.50283542, 0.45366404,\n", + " 0.38604981, 0.45310656, 0.43242414, 0.45769892, 0.43740257]),\n", + " array([0.697737 , 0.7285185 , 0.74073741, 0.5443046 , 0.62530419,\n", + " 0.65298325, 0.77010862, 0.59065507, 0.66937981, 0.55598691])],\n", + " 'rmse_std': [0.12089949291546664,\n", + " 0.07655891131422225,\n", + " 0.055366036864123516,\n", + " 0.031246551404113167,\n", + " 0.07419987281534979]},\n", + " 90: {'rmse': [array([0.92933434, 0.65042227, 0.82234897, 0.77023618, 0.66836863,\n", + " 0.92107577, 0.77129574, 0.78663625, 0.80956319, 0.79878541]),\n", + " array([0.79090432, 0.87537346, 0.75133874, 0.86595569, 0.82613158,\n", + " 0.80825972, 0.95229914, 1.00029129, 0.91787465, 0.67696987]),\n", + " array([0.99481393, 1.0055515 , 0.75792557, 1.02554954, 0.97356838,\n", + " 1.10275743, 0.91129203, 0.83042939, 0.94643869, 0.92099155]),\n", + " array([0.49183162, 0.50682853, 0.46536122, 0.60306949, 0.52749539,\n", + " 0.45459163, 0.53054983, 0.50742994, 0.5291524 , 0.51534896]),\n", + " array([0.62349215, 0.55279762, 0.64297245, 0.76298314, 0.57521928,\n", + " 0.56917365, 0.77942422, 0.74534364, 0.72668116, 0.73748615])],\n", + " 'rmse_std': [0.08546953156745585,\n", + " 0.09160564750010927,\n", + " 0.09388309230448638,\n", + " 0.038852247173645826,\n", + " 0.08355732996818074]},\n", + " 100: {'rmse': [array([1.04045639, 0.67025346, 0.80107475, 0.76953626, 0.82989402,\n", + " 0.73821852, 0.93046764, 0.54891392, 0.99904379, 0.68238419]),\n", + " array([0.85903369, 0.87769261, 1.02844213, 0.93061859, 0.79010772,\n", + " 0.97075989, 0.94487997, 0.83704409, 0.95810058, 0.93789027]),\n", + " array([1.05683277, 1.13141876, 0.88420804, 1.07705624, 0.99344815,\n", + " 1.04786755, 0.99548241, 0.91929861, 0.99752006, 0.83961389]),\n", + " array([0.57640194, 0.59363208, 0.53511562, 0.71635887, 0.60565362,\n", + " 0.52654513, 0.61065628, 0.58395028, 0.60349726, 0.59762075]),\n", + " array([0.68670119, 0.66242045, 0.70886123, 0.78454936, 0.81772217,\n", + " 0.90759664, 0.71637634, 0.76525914, 0.71153251, 0.7521363 ])],\n", + " 'rmse_std': [0.1462192469279573,\n", + " 0.06758115430225692,\n", + " 0.08609047902180741,\n", + " 0.04889549822660871,\n", + " 0.06842248539362279]},\n", + " 110: {'rmse': [array([1.12918644, 0.66636448, 0.74738688, 0.84448343, 0.7474447 ,\n", + " 0.66427973, 0.78020758, 0.85855111, 1.053857 , 0.74856621]),\n", + " array([0.87342759, 0.9189313 , 0.81043799, 0.75491776, 0.89794882,\n", + " 1.00969526, 0.93590653, 0.98759582, 0.89737107, 0.93326638]),\n", + " array([1.09337282, 1.15395226, 0.97495421, 1.13210054, 1.11431864,\n", + " 1.04645875, 1.2444213 , 1.14148127, 0.94036356, 0.89980083]),\n", + " array([0.6684465 , 0.68632792, 0.61220902, 0.83744307, 0.68986969,\n", + " 0.60380931, 0.6844738 , 0.66448304, 0.68118189, 0.68016027]),\n", + " array([0.79918568, 0.80092447, 0.78681151, 0.81093941, 0.82185763,\n", + " 0.887655 , 0.90589584, 0.87045354, 0.76507071, 0.77622438])],\n", + " 'rmse_std': [0.1474056253556985,\n", + " 0.07225635358963209,\n", + " 0.10204830529101577,\n", + " 0.05976206690248655,\n", + " 0.04621247388666876]},\n", + " 120: {'rmse': [array([0.9141297 , 0.62082432, 0.69252896, 0.98814943, 0.76297021,\n", + " 0.9106569 , 0.82077992, 0.66547354, 0.78924553, 0.85966904]),\n", + " array([0.9169644 , 0.86969474, 0.91267668, 0.8226001 , 1.04466998,\n", + " 1.05464076, 0.88644817, 0.86651354, 1.06454683, 0.99047135]),\n", + " array([1.12006979, 1.25407234, 1.20008349, 1.18956955, 1.22870078,\n", + " 1.12626035, 1.29920538, 1.2608156 , 1.29367082, 1.04061312]),\n", + " array([0.76561029, 0.65883428, 0.69437935, 0.75104706, 0.69978249,\n", + " 0.72724813, 0.50135001, 0.6517558 , 0.73613568, 0.73959689]),\n", + " array([0.90645037, 0.80209187, 0.87129778, 0.94093268, 0.93278076,\n", + " 0.99606324, 0.86874898, 0.98192334, 1.04505493, 0.7208504 ])],\n", + " 'rmse_std': [0.11306699496818505,\n", + " 0.08387072476693634,\n", + " 0.07961426563192224,\n", + " 0.07313740103834195,\n", + " 0.09100276849143851]},\n", + " 130: {'rmse': [array([0.70622585, 0.75741001, 0.94440662, 0.71436155, 0.95042566,\n", + " 0.85356204, 0.61608882, 0.64938097, 0.56998564, 0.84119779]),\n", + " array([0.95859236, 0.91011461, 0.9067229 , 0.85603531, 0.75817045,\n", + " 0.75578987, 1.02627164, 1.29908691, 0.93011662, 1.04565226]),\n", + " array([1.16251062, 1.3941231 , 1.22977602, 1.32208907, 1.37842222,\n", + " 1.24067088, 1.32977897, 1.32408153, 1.31809769, 1.31788691]),\n", + " array([0.86708176, 0.73114287, 0.76432051, 0.86502809, 0.76984218,\n", + " 0.82799266, 0.87937561, 0.62392546, 0.70587154, 0.72654128]),\n", + " array([0.95680905, 0.89445284, 1.03485634, 1.03616288, 1.15074845,\n", + " 0.98329111, 0.89069912, 0.8884503 , 0.86793876, 0.92869853])],\n", + " 'rmse_std': [0.1263516653526676,\n", + " 0.14960654106020577,\n", + " 0.06703400693538322,\n", + " 0.07892327738281142,\n", + " 0.08480109284597191]},\n", + " 140: {'rmse': [array([0.72445577, 0.76849586, 0.98870851, 0.67779435, 0.9495869 ,\n", + " 0.59440172, 0.9119564 , 1.06463636, 0.87725276, 0.80981099]),\n", + " array([0.98107991, 0.70670223, 0.80949025, 0.72368981, 1.14019419,\n", + " 0.857012 , 1.01620419, 0.69482117, 0.87540096, 0.69728099]),\n", + " array([1.23424184, 1.30489896, 1.29943664, 1.34410056, 1.33087826,\n", + " 1.34947752, 1.11011148, 1.46110815, 1.42268962, 1.2777539 ]),\n", + " array([0.93185841, 1.00703034, 0.79095787, 0.9807252 , 0.97373469,\n", + " 0.99536309, 0.84872148, 0.74895024, 0.74031764, 0.81482258]),\n", + " array([1.01287309, 1.06955072, 0.99906139, 1.01606617, 1.05703781,\n", + " 1.07547521, 0.98136726, 1.06705637, 1.03819688, 0.89242214])],\n", + " 'rmse_std': [0.1403731205378919,\n", + " 0.14671250580103892,\n", + " 0.09243462292464356,\n", + " 0.10039972097846804,\n", + " 0.05264503614080382]},\n", + " 150: {'rmse': [array([0.7397306 , 0.77907802, 0.98691497, 0.68054778, 0.88601432,\n", + " 0.79337621, 0.60557787, 0.74429203, 0.74182022, 0.58890858]),\n", + " array([0.86478845, 0.66751 , 0.79842915, 0.98673521, 0.84408132,\n", + " 0.79202335, 0.77617964, 1.19759526, 0.79734344, 0.76793043]),\n", + " array([1.32070291, 1.29818291, 1.27684331, 1.42746036, 1.50511125,\n", + " 1.46515262, 1.35555262, 1.36560567, 1.37076769, 1.42826527]),\n", + " array([1.02345863, 0.56422874, 0.9137183 , 0.72618435, 1.09505683,\n", + " 0.94362008, 0.9796221 , 1.06728223, 1.10168809, 0.9139733 ]),\n", + " array([1.10414083, 1.18475846, 0.93033761, 1.07239977, 0.92207216,\n", + " 0.94659596, 0.88240508, 1.2370221 , 1.35513541, 0.84934114])],\n", + " 'rmse_std': [0.11356864920884441,\n", + " 0.13930121234149623,\n", + " 0.07014897496892158,\n", + " 0.16208565500131547,\n", + " 0.1610533504023646]},\n", + " 160: {'rmse': [array([0.75134608, 0.79283277, 1.07665505, 0.63100252, 0.77063261,\n", + " 0.64354027, 0.68057501, 0.79478952, 0.64915349, 0.87015685]),\n", + " array([0.63541745, 0.81519906, 0.82886117, 0.46614224, 0.82614876,\n", + " 0.45229299, 0.70285357, 0.51439189, 0.73391236, 0.88414096]),\n", + " array([1.38336722, 1.3943375 , 1.28384714, 1.43364353, 1.406559 ,\n", + " 1.41551795, 1.4949701 , 1.38964605, 1.37424819, 1.42460714]),\n", + " array([1.11262533, 1.20714317, 0.55013033, 1.00880295, 0.62220261,\n", + " 0.57982736, 0.98190027, 0.61125915, 0.97471729, 0.5913273 ]),\n", + " array([1.04018768, 0.97807638, 1.24444957, 1.17047338, 1.30111424,\n", + " 1.37078676, 1.42982497, 1.3401764 , 1.34553039, 1.23114212])],\n", + " 'rmse_std': [0.1277933624769025,\n", + " 0.15282250001968198,\n", + " 0.050607361450725384,\n", + " 0.24220774357797442,\n", + " 0.13828913472461868]},\n", + " 170: {'rmse': [array([0.76175372, 0.7941689 , 1.04835157, 0.62639784, 0.74253749,\n", + " 0.76273131, 0.82229 , 0.64538124, 0.80236682, 1.02734942]),\n", + " array([0.61587973, 0.72896761, 0.61401443, 0.52919783, 0.64100167,\n", + " 0.83671165, 0.6038792 , 0.70611702, 0.38971743, 0.56739542]),\n", + " array([1.42536377, 1.46299542, 1.40839993, 1.52035449, 1.46314197,\n", + " 1.42426184, 1.46956083, 1.37149952, 1.31778231, 1.37155313]),\n", + " array([1.1982825 , 1.2613151 , 0.70961029, 0.64377267, 0.75074961,\n", + " 0.62596813, 0.86739876, 1.04960803, 0.67012209, 0.5913303 ]),\n", + " array([1.10881555, 1.42094593, 1.28537402, 1.17791728, 1.36582822,\n", + " 1.16495058, 1.29220715, 1.23801188, 1.21036144, 1.34929902])],\n", + " 'rmse_std': [0.1319052607020199,\n", + " 0.11442988838089194,\n", + " 0.05607547683531553,\n", + " 0.23461343154977451,\n", + " 0.09397660928027625]},\n", + " 180: {'rmse': [array([0.77048074, 0.80808027, 1.06800051, 0.6427345 , 0.58125577,\n", + " 0.84140938, 0.8586086 , 0.67832865, 0.83939537, 0.99068776]),\n", + " array([0.60862716, 0.74829817, 0.59281006, 0.75039913, 0.47009362,\n", + " 0.46745419, 0.54561024, 0.80336137, 0.56908796, 0.83728405]),\n", + " array([1.63353394, 1.49716118, 1.65939884, 1.43182045, 1.42508895,\n", + " 1.53242454, 1.45090614, 1.46965189, 1.4384518 , 1.42479838]),\n", + " array([0.70258478, 0.82916052, 1.17436591, 0.56081661, 0.63663978,\n", + " 0.59391602, 0.54312218, 0.62108727, 0.6072987 , 0.60028435]),\n", + " array([1.1987026 , 1.15201953, 1.42105883, 1.30549832, 1.25022279,\n", + " 1.35119469, 1.51957957, 1.45151626, 1.41612032, 1.26303713])],\n", + " 'rmse_std': [0.14233273060512058,\n", + " 0.12857249186445144,\n", + " 0.08197459963232763,\n", + " 0.18000506142293685,\n", + " 0.11275870579540288]},\n", + " 190: {'rmse': [array([0.77890689, 0.81117611, 1.12331205, 0.63514721, 0.72128073,\n", + " 0.77587672, 0.99474551, 0.79011672, 0.89469681, 0.55738144]),\n", + " array([0.59536177, 0.75143892, 0.73073059, 0.51100472, 0.50470629,\n", + " 0.50742648, 0.68722993, 0.7694655 , 0.72286152, 0.84835039]),\n", + " array([1.56813033, 1.42418044, 1.44814146, 1.39844881, 1.42229801,\n", + " 1.37021516, 1.49864399, 1.37537464, 1.39524293, 1.46753639]),\n", + " array([0.64130075, 0.85066209, 0.55624795, 0.65237769, 0.68486878,\n", + " 0.58255822, 0.6672524 , 0.61751906, 0.57977729, 0.56147694]),\n", + " array([1.30767499, 1.21802736, 1.45655814, 1.33374856, 1.37040649,\n", + " 1.16210046, 1.50311239, 0.97860308, 1.21009418, 1.34059767])],\n", + " 'rmse_std': [0.15627776800826182,\n", + " 0.11798574163494,\n", + " 0.05824059033887865,\n", + " 0.08240010221910221,\n", + " 0.14465998632989843]},\n", + " 200: {'rmse': [array([0.78903792, 0.84143198, 0.71352549, 0.94284964, 0.38327467,\n", + " 0.95321286, 0.84008594, 0.89222285, 0.74068282, 0.93226758]),\n", + " array([0.58920625, 0.72878518, 0.67373454, 0.45784713, 0.53835973,\n", + " 0.69694865, 0.68097327, 0.58254862, 0.71636256, 0.69258267]),\n", + " array([1.50118025, 1.40647296, 1.44029657, 1.40156308, 1.40249901,\n", + " 1.34430489, 1.53237894, 1.39001732, 1.38531921, 1.39447321]),\n", + " array([0.60659331, 0.80617361, 0.595693 , 0.68402066, 0.60401443,\n", + " 0.62593588, 0.67293689, 0.69838398, 0.58647507, 0.62744887]),\n", + " array([1.43389423, 1.50150812, 1.60353611, 1.5472882 , 1.23370057,\n", + " 1.12171357, 1.35652008, 1.383547 , 1.55132346, 1.30772386])],\n", + " 'rmse_std': [0.1605921065777003,\n", + " 0.0847042669529824,\n", + " 0.05379893779273422,\n", + " 0.06362384422635518,\n", + " 0.14597297521241945]}}}" + ] + }, + "execution_count": 20, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "metric" + ] + }, + { + "cell_type": "code", + "execution_count": 64, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "True\n", + "True\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n" + ] + }, + { + "data": { + "text/plain": [ + "Text(0.5, 1.0, 'PPO for Quadrotor 2D')" + ] + }, + "execution_count": 64, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "fig = plt.figure(figsize=(6, 3))\n", + "# for method in metric.keys():\n", + "method = 'PPO'\n", + "temp, temp_std1, temp_std2 = [], [], []\n", + "traj_success_till = 200\n", + "for ns in noise_scale:\n", + " data = np.array(metric[method][ns]['rmse'])\n", + " temp.append(data.mean())\n", + " temp_std1.append(data.mean() - data.std())\n", + " temp_std2.append(data.mean() + data.std())\n", + " print(all(metric[method][ns]['success']))\n", + " if not all(metric[method][ns]['success']) and traj_success_till > ns:\n", + " traj_success_till = ns\n", + "plt.plot(noise_scale, temp, color=colors[method], label='mean')\n", + "plt.fill_between(noise_scale, \n", + " temp_std1, \n", + " temp_std2, color=colors[method], alpha=0.1, label='std')\n", + "\n", + "plt.fill_between([traj_success_till, 200], [1, 1], color='r', alpha=0.25, label='early stop')\n", + "plt.plot(noise_scale, [0.1]*len(noise_scale), color='grey', linestyle='--', label='rmse=0.1')\n", + "\n", + "plt.legend()\n", + "plt.ylim(0,1)\n", + "# plt.xscale(\"log\")\n", + "# plt.gca().invert_xaxis()\n", + "# plt.yscale(\"log\")\n", + "plt.xlabel(\"Noise amplification factor\")\n", + "plt.ylabel(\"RMSE\")\n", + "plt.title(\"PPO for Quadrotor 2D\")\n", + "# plt.savefig(\"perf1.pdf\",bbox_inches=\"tight\", pad_inches=0.0)" + ] + }, + { + "cell_type": "code", + "execution_count": 65, "metadata": {}, "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "True\n", + "True\n", + "True\n", + "True\n", + "True\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n", + "False\n" + ] + }, { "data": { "text/plain": [ - "(array([ 5.56661044, 8.98567327, 6.40123258, 14.21983029, 13.08274237,\n", - " 8.77096302, 8.71078224, 5.30294769, 4.94162143, 3.66671972,\n", - " 3.31768475, 2.55528452, 2.02426006, 2.07484464, 1.40722345,\n", - " 1.84371323]),\n", - " array([ 5.56661044, 8.98567327, 6.40123258, 14.21983029, 13.08274237,\n", - " 8.77096302, 8.71078224, 5.30294769, 4.94162143, 3.66671972,\n", - " 3.31768475, 2.55528452, 2.02426006, 2.07484464, 1.40722345,\n", - " 1.84371323]))" + "Text(0.5, 1.0, 'SAC for Quadrotor 2D')" ] }, - "execution_count": 15, + "execution_count": 65, "metadata": {}, "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" } ], "source": [ - "np.mean(temp[:,3,:], axis=0),np.mean(temp[:,4,:], axis=0)" + "fig = plt.figure(figsize=(6, 3))\n", + "# for method in metric.keys():\n", + "method = 'SAC'\n", + "temp, temp_std1, temp_std2 = [], [], []\n", + "traj_success_till = 200\n", + "for ns in noise_scale:\n", + " data = np.array(metric[method][ns]['rmse'])\n", + " temp.append(data.mean())\n", + " temp_std1.append(data.mean() - data.std())\n", + " temp_std2.append(data.mean() + data.std())\n", + " print(all(metric[method][ns]['success']))\n", + " if not all(metric[method][ns]['success']) and traj_success_till > ns:\n", + " traj_success_till = ns\n", + "plt.plot(noise_scale, temp, color=colors[method], label='mean')\n", + "plt.fill_between(noise_scale, \n", + " temp_std1, \n", + " temp_std2, color=colors[method], alpha=0.1, label='std')\n", + "\n", + "plt.fill_between([traj_success_till, 200], [1, 1], color='r', alpha=0.25, label='early stop')\n", + "plt.plot(noise_scale, [0.1]*len(noise_scale), color='grey', linestyle='--', label='rmse=0.1')\n", + "\n", + "plt.legend()\n", + "plt.ylim(0,1)\n", + "# plt.xscale(\"log\")\n", + "# plt.gca().invert_xaxis()\n", + "# plt.yscale(\"log\")\n", + "plt.xlabel(\"Noise amplification factor\")\n", + "plt.ylabel(\"RMSE\")\n", + "plt.title(\"SAC for Quadrotor 2D\")\n", + "# plt.savefig(\"perf1.pdf\",bbox_inches=\"tight\", pad_inches=0.0)" ] }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": 66, + "metadata": {}, + "outputs": [], + "source": [ + "np.save('compiled_metric.npy',metric, allow_pickle=True)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, { "cell_type": "code", "execution_count": null, diff --git a/examples/rl/rl_experiment.py b/examples/rl/rl_experiment.py index cd77a81b3..d5c071e7e 100644 --- a/examples/rl/rl_experiment.py +++ b/examples/rl/rl_experiment.py @@ -12,7 +12,7 @@ from safe_control_gym.utils.registration import make -def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'): +def run(gui=False, plot=True, n_episodes=10, n_steps=None, curr_path='.'): """Main function to run RL experiments. Args: @@ -38,6 +38,8 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'): else: system = config.task + # config.task_config.disturbances.observation[0].std = [config.task_config.noise_scale*i + # for i in config.task_config.disturbances.observation[0].std] env_func = partial(make, config.task, **config.task_config) @@ -51,7 +53,11 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'): # Load state_dict from trained. # ctrl.load(f'{curr_path}/models/{config.algo}/{config.algo}_model_{system}_{task}.pt') - ctrl.load(f'{curr_path}/models/{config.algo}/model_best.pt') + # ctrl.load(f'{curr_path}/models/{config.algo}/model_best.pt') + if 'pretrain_path' in config.keys(): + ctrl.load(config.pretrain_path+"/model_latest.pt") + else: + ctrl.load(f'{curr_path}/models/{config.algo}/model_latest.pt') # Remove temporary files and directories shutil.rmtree(f'{curr_path}/temp', ignore_errors=True) @@ -60,6 +66,9 @@ def run(gui=False, plot=True, n_episodes=1, n_steps=None, curr_path='.'): experiment = BaseExperiment(env, ctrl) results, metrics = experiment.run_evaluation(n_episodes=n_episodes, n_steps=n_steps) ctrl.close() + # metrics['noise_scale'] = config.task_config.noise_scale + # temp = config.pretrain_path+"/metric_"+str(config.task_config.noise_scale)+".npy" + # np.save(temp, metrics, allow_pickle=True) if plot is True: if system == Environment.CARTPOLE: diff --git a/examples/rl/rl_experiment.sh b/examples/rl/rl_experiment.sh index 7c12ae683..96b4fb6fe 100755 --- a/examples/rl/rl_experiment.sh +++ b/examples/rl/rl_experiment.sh @@ -13,6 +13,7 @@ ALGO='ppo' #ALGO='sac' #ALGO='td3' #ALGO='safe_explorer_ppo' +#ALGO='dppo' if [ "$SYS" == 'cartpole' ]; then SYS_NAME=$SYS @@ -21,12 +22,19 @@ else fi # RL Experiment -python3 ./rl_experiment.py \ - --task ${SYS_NAME} \ - --algo ${ALGO} \ - --overrides \ - ./config_overrides/${SYS}/${SYS}_${TASK}.yaml \ - ./config_overrides/${SYS}/${ALGO}_${SYS}.yaml \ - --kv_overrides \ - algo_config.training=False \ - task_config.randomized_init=True +#for NS in {1,10,20,30,40,50,60,70,80,90,100,110,120,130,140,150,160,170,180,190,200} +#do +for SEED in {0..0} +do + python3 ./rl_experiment.py \ + --task ${SYS_NAME} \ + --algo ${ALGO} \ + --overrides \ + ./config_overrides/${SYS}/${SYS}_${TASK}.yaml \ + ./config_overrides/${SYS}/${ALGO}_${SYS}.yaml \ + --kv_overrides \ + algo_config.training=False \ + task_config.randomized_init=True +# --pretrain_path ./Results/LSY_pc/${SYS}_${ALGO}_data/Long_run/${SEED} +done +#done \ No newline at end of file diff --git a/examples/rl/train_rl_model.sh b/examples/rl/train_rl_model.sh index 7ee1e5fae..9d99d3ad1 100755 --- a/examples/rl/train_rl_model.sh +++ b/examples/rl/train_rl_model.sh @@ -9,10 +9,11 @@ SYS='quadrotor_2D_attitude' #TASK='stab' TASK='track' -ALGO='ppo' -#ALGO='sac' +#ALGO='ppo' +ALGO='sac' #ALGO='td3' #ALGO='ddpg' +#ALGO='dppo' #ALGO='safe_explorer_ppo' if [ "$SYS" == 'cartpole' ]; then @@ -55,8 +56,9 @@ do ./config_overrides/${SYS}/${SYS}_${TASK}.yaml \ --output_dir ./Results/${SYS}_${ALGO}_data/${SEED}/ \ --seed ${SEED} \ + --use_gpu\ --kv_overrides \ - task_config.randomized_init=True + task_config.randomized_init=True # --pretrain_path ./models/${ALGO}/model_latest.pt done diff --git a/safe_control_gym/controllers/ppo/ppo.py b/safe_control_gym/controllers/ppo/ppo.py index d702f5fa9..2be2b2488 100644 --- a/safe_control_gym/controllers/ppo/ppo.py +++ b/safe_control_gym/controllers/ppo/ppo.py @@ -216,6 +216,52 @@ def select_action(self, obs, info=None): action = self.agent.ac.act(obs) return action + def train_step(self): + """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) + obs = self.obs + start = time.time() + for _ in range(self.rollout_steps): + with torch.no_grad(): + act, v, logp = self.agent.ac.step(torch.FloatTensor(obs).to(self.device)) + next_obs, rew, done, info = self.env.step(act) + next_obs = self.obs_normalizer(next_obs) + rew = self.reward_normalizer(rew, done) + mask = 1 - done.astype(float) + # Time truncation is not the same as true termination. + terminal_v = np.zeros_like(v) + for idx, inf in enumerate(info['n']): + if 'terminal_info' not in inf: + continue + inff = inf['terminal_info'] + if 'TimeLimit.truncated' in inff and inff['TimeLimit.truncated']: + terminal_obs = inf['terminal_observation'] + terminal_obs_tensor = torch.FloatTensor(terminal_obs).unsqueeze(0).to(self.device) + terminal_val = self.agent.ac.critic(terminal_obs_tensor).squeeze().detach().cpu().numpy() + terminal_v[idx] = terminal_val + rollouts.push({'obs': obs, 'act': act, 'rew': rew, 'mask': mask, 'v': v, 'logp': logp, 'terminal_v': terminal_v}) + obs = next_obs + self.obs = obs + self.total_steps += self.rollout_batch_size * self.rollout_steps + # Learn from rollout batch. + last_val = self.agent.ac.critic(torch.FloatTensor(obs).to(self.device)).detach().cpu().numpy() + ret, adv = compute_returns_and_advantages(rollouts.rew, + rollouts.v, + rollouts.mask, + rollouts.terminal_v, + last_val, + gamma=self.gamma, + use_gae=self.use_gae, + gae_lambda=self.gae_lambda) + rollouts.ret = ret + # Prevent divide-by-0 for repetitive tasks. + rollouts.adv = (adv - adv.mean()) / (adv.std() + 1e-6) + results = self.agent.update(rollouts, self.device) + results.update({'step': self.total_steps, 'elapsed_time': time.time() - start}) + return results + def run(self, env=None, render=False, @@ -237,9 +283,9 @@ def run(self, obs, info = env.reset() obs = self.obs_normalizer(obs) - ep_returns, ep_lengths, eval_return = [], [], 0.0 + ep_returns, ep_lengths = [], [] frames = [] - mse, ep_rmse_mean, ep_rmse_std = [], [], [] + mse, ep_rmse = [], [] while len(ep_returns) < n_episodes: action = self.select_action(obs=obs, info=info) obs, _, done, info = env.step(action) @@ -251,8 +297,7 @@ def run(self, print(f'obs {obs} | act {action}') if done: assert 'episode' in info - ep_rmse_mean.append(np.array(mse).mean()**0.5) - ep_rmse_std.append(np.array(mse).std()) + ep_rmse.append(np.array(mse).mean()**0.5) mse = [] ep_returns.append(info['episode']['r']) ep_lengths.append(info['episode']['l']) @@ -262,8 +307,8 @@ def run(self, ep_lengths = np.asarray(ep_lengths) ep_returns = np.asarray(ep_returns) eval_results = {'ep_returns': ep_returns, 'ep_lengths': ep_lengths, - 'rmse': np.array(ep_rmse_mean).mean(), - 'rmse_std': np.array(ep_rmse_std).mean()} + 'rmse': np.array(ep_rmse).mean(), + 'rmse_std': np.array(ep_rmse).std()} if len(frames) > 0: eval_results['frames'] = frames # Other episodic stats from evaluation env. @@ -272,52 +317,6 @@ def run(self, eval_results.update(queued_stats) return eval_results - def train_step(self): - """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) - obs = self.obs - start = time.time() - for _ in range(self.rollout_steps): - with torch.no_grad(): - act, v, logp = self.agent.ac.step(torch.FloatTensor(obs).to(self.device)) - next_obs, rew, done, info = self.env.step(act) - next_obs = self.obs_normalizer(next_obs) - rew = self.reward_normalizer(rew, done) - mask = 1 - done.astype(float) - # Time truncation is not the same as true termination. - terminal_v = np.zeros_like(v) - for idx, inf in enumerate(info['n']): - if 'terminal_info' not in inf: - continue - inff = inf['terminal_info'] - if 'TimeLimit.truncated' in inff and inff['TimeLimit.truncated']: - terminal_obs = inf['terminal_observation'] - terminal_obs_tensor = torch.FloatTensor(terminal_obs).unsqueeze(0).to(self.device) - terminal_val = self.agent.ac.critic(terminal_obs_tensor).squeeze().detach().cpu().numpy() - terminal_v[idx] = terminal_val - rollouts.push({'obs': obs, 'act': act, 'rew': rew, 'mask': mask, 'v': v, 'logp': logp, 'terminal_v': terminal_v}) - obs = next_obs - self.obs = obs - self.total_steps += self.rollout_batch_size * self.rollout_steps - # Learn from rollout batch. - last_val = self.agent.ac.critic(torch.FloatTensor(obs).to(self.device)).detach().cpu().numpy() - ret, adv = compute_returns_and_advantages(rollouts.rew, - rollouts.v, - rollouts.mask, - rollouts.terminal_v, - last_val, - gamma=self.gamma, - use_gae=self.use_gae, - gae_lambda=self.gae_lambda) - rollouts.ret = ret - # Prevent divide-by-0 for repetitive tasks. - rollouts.adv = (adv - adv.mean()) / (adv.std() + 1e-6) - results = self.agent.update(rollouts, self.device) - results.update({'step': self.total_steps, 'elapsed_time': time.time() - start}) - return results - def log_step(self, results ): diff --git a/safe_control_gym/controllers/sac/sac.py b/safe_control_gym/controllers/sac/sac.py index 4ff5f28ec..4725f8533 100644 --- a/safe_control_gym/controllers/sac/sac.py +++ b/safe_control_gym/controllers/sac/sac.py @@ -1,4 +1,4 @@ -'''Soft Actor Critic (SAC) +"""Soft Actor Critic (SAC) Adapted from https://github.com/openai/spinningup/blob/master/spinup/algos/pytorch/sac/sac.py @@ -10,7 +10,7 @@ * [rlkit - sac](https://github.com/vitchyr/rlkit/tree/7daf34b0ef2277d545a0ee792399a2ae6c3fb6ad/rlkit/torch/sac) * [ray rllib - sac](https://github.com/ray-project/ray/tree/master/rllib/agents/sac) * [curl - curl_sac](https://github.com/MishaLaskin/curl/blob/master/curl_sac.py) -''' +""" import os import time @@ -32,7 +32,7 @@ class SAC(BaseController): - '''soft actor critic.''' + """soft actor critic.""" def __init__(self, env_func, @@ -91,7 +91,7 @@ def __init__(self, self.logger = ExperimentLogger(output_dir, log_file_out=log_file_out, use_tensorboard=use_tensorboard) def reset(self): - '''Prepares for training or testing.''' + """Prepares for training or testing.""" if self.training: # set up stats tracking self.env.add_tracker('constraint_violation', 0) @@ -110,14 +110,14 @@ 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() self.logger.close() def save(self, path, save_buffer=False): - '''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) @@ -141,7 +141,7 @@ def save(self, path, save_buffer=False): torch.save(state_dict, path) def load(self, path): - '''Restores model and experiment given checkpoint path.''' + """Restores model and experiment given checkpoint path.""" state = torch.load(path) # restore params @@ -160,7 +160,7 @@ def load(self, path): self.logger.load(self.total_steps) 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) interval_save = np.zeros_like(step_interval, dtype=bool) @@ -186,10 +186,11 @@ def learn(self, env=None, **kwargs): if self.eval_interval and self.total_steps % self.eval_interval == 0: eval_results = self.run(env=self.eval_env, n_episodes=self.eval_batch_size) results['eval'] = eval_results - self.logger.info('Eval | ep_lengths {:.2f} +/- {:.2f} | ep_return {:.3f} +/- {:.3f}'.format(eval_results['ep_lengths'].mean(), - eval_results['ep_lengths'].std(), - eval_results['ep_returns'].mean(), - eval_results['ep_returns'].std())) + self.logger.info('Eval | ep_lengths {:.2f} +/- {:.2f} | ' + 'ep_return {:.3f} +/- {:.3f}'.format(eval_results['ep_lengths'].mean(), + eval_results['ep_lengths'].std(), + eval_results['ep_returns'].mean(), + eval_results['ep_returns'].std())) # save best model eval_score = eval_results['ep_returns'].mean() eval_best_score = getattr(self, 'eval_best_score', -np.infty) @@ -202,7 +203,7 @@ def learn(self, env=None, **kwargs): 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. @@ -210,7 +211,7 @@ 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) @@ -218,62 +219,8 @@ def select_action(self, obs, info=None): return action - def run(self, env=None, render=False, n_episodes=10, verbose=False, **kwargs): - '''Runs evaluation with current policy.''' - self.agent.eval() - self.obs_normalizer.set_read_only() - if env is None: - env = self.env - else: - if not is_wrapped(env, RecordEpisodeStatistics): - env = RecordEpisodeStatistics(env, n_episodes) - # Add episodic stats to be tracked. - env.add_tracker('constraint_violation', 0, mode='queue') - env.add_tracker('constraint_values', 0, mode='queue') - env.add_tracker('mse', 0, mode='queue') - - obs, info = env.reset() - obs = self.obs_normalizer(obs) - ep_returns, ep_lengths = [], [] - frames = [] - mse, ep_rmse_mean, ep_rmse_std = [], [], [] - while len(ep_returns) < n_episodes: - action = self.select_action(obs=obs, info=info) - - obs, _, done, info = env.step(action) - mse.append(info["mse"]) - if render: - env.render() - frames.append(env.render('rgb_array')) - if verbose: - print(f'obs {obs} | act {action}') - - if done: - assert 'episode' in info - ep_rmse_mean.append(np.array(mse).mean()**0.5) - ep_rmse_std.append(np.array(mse).std()) - mse = [] - ep_returns.append(info['episode']['r']) - ep_lengths.append(info['episode']['l']) - obs, info = env.reset() - obs = self.obs_normalizer(obs) - - # collect evaluation results - ep_lengths = np.asarray(ep_lengths) - ep_returns = np.asarray(ep_returns) - eval_results = {'ep_returns': ep_returns, 'ep_lengths': ep_lengths, - 'rmse': np.array(ep_rmse_mean).mean(), - 'rmse_std': np.array(ep_rmse_std).mean()} - if len(frames) > 0: - eval_results['frames'] = frames - # Other episodic stats from evaluation env. - if len(env.queued_stats) > 0: - queued_stats = {k: np.asarray(v) for k, v in env.queued_stats.items()} - eval_results.update(queued_stats) - return eval_results - def train_step(self, **kwargs): - '''Performs a training step.''' + """Performs a training step.""" self.agent.train() self.obs_normalizer.unset_read_only() obs = self.obs @@ -343,8 +290,61 @@ def train_step(self, **kwargs): results.update({'step': self.total_steps, 'elapsed_time': time.time() - start}) return results + def run(self, env=None, render=False, n_episodes=10, verbose=False, **kwargs): + """Runs evaluation with current policy.""" + self.agent.eval() + self.obs_normalizer.set_read_only() + if env is None: + env = self.env + else: + if not is_wrapped(env, RecordEpisodeStatistics): + env = RecordEpisodeStatistics(env, n_episodes) + # Add episodic stats to be tracked. + env.add_tracker('constraint_violation', 0, mode='queue') + env.add_tracker('constraint_values', 0, mode='queue') + env.add_tracker('mse', 0, mode='queue') + + obs, info = env.reset() + obs = self.obs_normalizer(obs) + ep_returns, ep_lengths = [], [] + frames = [] + mse, ep_rmse = [], [] + while len(ep_returns) < n_episodes: + action = self.select_action(obs=obs, info=info) + + obs, _, done, info = env.step(action) + mse.append(info["mse"]) + if render: + env.render() + frames.append(env.render('rgb_array')) + if verbose: + print(f'obs {obs} | act {action}') + + if done: + assert 'episode' in info + ep_rmse.append(np.array(mse).mean()**0.5) + mse = [] + ep_returns.append(info['episode']['r']) + ep_lengths.append(info['episode']['l']) + obs, info = env.reset() + obs = self.obs_normalizer(obs) + + # collect evaluation results + ep_lengths = np.asarray(ep_lengths) + ep_returns = np.asarray(ep_returns) + eval_results = {'ep_returns': ep_returns, 'ep_lengths': ep_lengths, + 'rmse': np.array(ep_rmse).mean(), + 'rmse_std': np.array(ep_rmse).std()} + if len(frames) > 0: + eval_results['frames'] = frames + # Other episodic stats from evaluation env. + if len(env.queued_stats) > 0: + queued_stats = {k: np.asarray(v) for k, v in env.queued_stats.items()} + eval_results.update(queued_stats) + return eval_results + 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/td3/td3.py b/safe_control_gym/controllers/td3/td3.py index 1997be00b..cb40a9c2c 100644 --- a/safe_control_gym/controllers/td3/td3.py +++ b/safe_control_gym/controllers/td3/td3.py @@ -56,7 +56,8 @@ def __init__(self, tau=self.tau, actor_lr=self.actor_lr, critic_lr=self.critic_lr, - activation=self.activation) + activation=self.activation, + device=self.device) self.agent.to(self.device) # pre-/post-processing @@ -198,54 +199,6 @@ def select_action(self, obs, info=None): return action - def run(self, env=None, render=False, n_episodes=10, verbose=False, **kwargs): - """Runs evaluation with current policy.""" - self.agent.eval() - self.obs_normalizer.set_read_only() - if env is None: - env = self.env - else: - if not is_wrapped(env, RecordEpisodeStatistics): - env = RecordEpisodeStatistics(env, n_episodes) - # Add episodic stats to be tracked. - env.add_tracker('constraint_violation', 0, mode='queue') - env.add_tracker('constraint_values', 0, mode='queue') - env.add_tracker('mse', 0, mode='queue') - - obs, info = env.reset() - obs = self.obs_normalizer(obs) - ep_returns, ep_lengths = [], [] - frames = [] - - while len(ep_returns) < n_episodes: - action = self.select_action(obs=obs, info=info) - - obs, _, done, info = env.step(action) - if render: - env.render() - frames.append(env.render('rgb_array')) - if verbose: - print(f'obs {obs} | act {action}') - - if done: - assert 'episode' in info - ep_returns.append(info['episode']['r']) - ep_lengths.append(info['episode']['l']) - obs, info = env.reset() - obs = self.obs_normalizer(obs) - - # collect evaluation results - ep_lengths = np.asarray(ep_lengths) - ep_returns = np.asarray(ep_returns) - eval_results = {'ep_returns': ep_returns, 'ep_lengths': ep_lengths} - if len(frames) > 0: - eval_results['frames'] = frames - # Other episodic stats from evaluation env. - if len(env.queued_stats) > 0: - queued_stats = {k: np.asarray(v) for k, v in env.queued_stats.items()} - eval_results.update(queued_stats) - return eval_results - def train_step(self, **kwargs): """Performs a training step.""" self.agent.train() @@ -314,6 +267,57 @@ def train_step(self, **kwargs): results.update({'step': self.total_steps, 'elapsed_time': time.time() - start}) return results + def run(self, env=None, render=False, n_episodes=10, verbose=False, **kwargs): + """Runs evaluation with current policy.""" + self.agent.eval() + self.obs_normalizer.set_read_only() + if env is None: + env = self.env + else: + if not is_wrapped(env, RecordEpisodeStatistics): + env = RecordEpisodeStatistics(env, n_episodes) + # Add episodic stats to be tracked. + env.add_tracker('constraint_violation', 0, mode='queue') + env.add_tracker('constraint_values', 0, mode='queue') + env.add_tracker('mse', 0, mode='queue') + + obs, info = env.reset() + obs = self.obs_normalizer(obs) + ep_returns, ep_lengths = [], [] + frames = [] + mse, ep_rmse = [], [] + while len(ep_returns) < n_episodes: + action = self.select_action(obs=obs, info=info) + obs, _, done, info = env.step(action) + mse.append(info["mse"]) + if render: + env.render() + frames.append(env.render('rgb_array')) + if verbose: + print(f'obs {obs} | act {action}') + if done: + assert 'episode' in info + ep_rmse.append(np.array(mse).mean()**0.5) + mse = [] + ep_returns.append(info['episode']['r']) + ep_lengths.append(info['episode']['l']) + obs, info = env.reset() + obs = self.obs_normalizer(obs) + + # collect evaluation results + ep_lengths = np.asarray(ep_lengths) + ep_returns = np.asarray(ep_returns) + eval_results = {'ep_returns': ep_returns, 'ep_lengths': ep_lengths, + 'rmse': np.array(ep_rmse).mean(), + 'rmse_std': np.array(ep_rmse).std()} + if len(frames) > 0: + eval_results['frames'] = frames + # Other episodic stats from evaluation env. + if len(env.queued_stats) > 0: + queued_stats = {k: np.asarray(v) for k, v in env.queued_stats.items()} + eval_results.update(queued_stats) + return eval_results + def log_step(self, results): """Does logging after a training step.""" step = results['step'] @@ -362,7 +366,8 @@ def log_step(self, results): eval_ep_lengths = results['eval']['ep_lengths'] eval_ep_returns = results['eval']['ep_returns'] eval_constraint_violation = results['eval']['constraint_violation'] - eval_mse = results['eval']['mse'] + eval_rmse = results['eval']['rmse'] + eval_rmse_std = results['eval']['rmse_std'] self.logger.add_scalars( { 'ep_length': eval_ep_lengths.mean(), @@ -370,7 +375,8 @@ def log_step(self, results): 'ep_return_std': eval_ep_returns.std(), 'ep_reward': (eval_ep_returns / eval_ep_lengths).mean(), 'constraint_violation': eval_constraint_violation.mean(), - 'mse': eval_mse.mean() + 'rmse': eval_rmse, + 'rmse_std': eval_rmse_std }, step, prefix='stat_eval') diff --git a/safe_control_gym/controllers/td3/td3_utils.py b/safe_control_gym/controllers/td3/td3_utils.py index f78b153b7..c5d9ec2b0 100644 --- a/safe_control_gym/controllers/td3/td3_utils.py +++ b/safe_control_gym/controllers/td3/td3_utils.py @@ -30,21 +30,24 @@ def __init__(self, actor_lr=0.001, critic_lr=0.001, activation='relu', + device=None, **kwargs): # 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.action_space_low = torch.FloatTensor(low).to(device) + self.action_space_high = torch.FloatTensor(high).to(device) self.gamma = gamma self.eps = eps self.tau = tau self.activation = activation + self.device = device # model - self.ac = MLPActorCritic(obs_space, act_space,eps=self.eps, hidden_dims=[hidden_dim] * 2, activation=self.activation) + self.ac = MLPActorCritic(obs_space, act_space, eps=self.eps, + hidden_dims=[hidden_dim] * 2, activation=self.activation) # target networks self.ac_targ = deepcopy(self.ac) @@ -115,7 +118,7 @@ def compute_q_loss(self, batch): critic_loss = q1_loss + q2_loss return critic_loss - def update(self, batch): + def update(self, batch, device=None): """Updates model parameters based on current training batch.""" results = defaultdict(list) 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 ed722f4d5..662d38b48 100644 --- a/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py +++ b/safe_control_gym/envs/gym_pybullet_drones/base_aviary.py @@ -839,12 +839,12 @@ def setup_dynamics_si_expression(self): Pitch = cs.MX.sym('P') U = cs.vertcat(Thrust, Pitch) X_dot = cs.vertcat(x_dot, - (18.112984649321753 * Thrust + 3.7613154938448576) * cs.sin(theta), + (18.1130 * Thrust + 3.6800) * cs.sin(theta) - 0.0080, z_dot, - (18.112984649321753 * Thrust + 3.7613154938448576) * cs.cos(theta) - g, + (18.1130 * Thrust + 3.6800) * cs.cos(theta) - g, theta_dot, # 60 * (60 * (P - theta) - theta_dot) - -143.9 * theta - 13.02 * theta_dot + 122.5 * Pitch + -140.8000 * theta -13.4000 * theta_dot + 124.8000 * Pitch ) self.X_dot_fun = cs.Function("X_dot", [X, U], [X_dot]) diff --git a/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py b/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py index f695dd241..1c61aabf0 100644 --- a/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py +++ b/safe_control_gym/envs/gym_pybullet_drones/quadrotor.py @@ -382,7 +382,6 @@ def reset(self, seed=None): obs (ndarray): The initial state of the environment. info (dict): A dictionary with information about the dynamics and constraints symbolic models. """ - super().before_reset(seed=seed) # PyBullet simulation reset. super()._reset_simulation() @@ -901,8 +900,16 @@ def _preprocess_control(self, action): self.current_physical_action = self.current_physical_action + self.adv_action self.current_noisy_physical_action = self.current_physical_action + # Identified dynamics model works with collective thrust and pitch directly + # No need to compute RPMs, (save compute) + self.current_clipped_action = np.clip(self.current_noisy_physical_action, + self.physical_action_bounds[0], + self.physical_action_bounds[1])[0] + if self.PHYSICS == Physics.DYN_SI: + return None + if self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE or self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE_5S: - collective_thrust, pitch = action + collective_thrust, pitch = self.current_clipped_action # rpm = self.attitude_control._dslPIDAttitudeControl(individual_thrust, # self.quat[0], np.array([0, pitch, 0])) # input thrust is pwm @@ -969,7 +976,6 @@ def denormalize_action(self, action): thrust = (1 + self.norm_act_scale * action[0]) * self.hover_thrust # thrust = self.attitude_control.thrust2pwm(thrust) - # thrust = self.HOVER_RPM * (1+0.05*action[0]) action = np.array([thrust, action[1]]) @@ -984,7 +990,6 @@ def _get_observation(self): Returns: obs (ndarray): The state of the quadrotor, of size 2 or 6 depending on QUAD_TYPE. """ - full_state = self._get_drone_state_vector(0) pos, _, rpy, vel, ang_v, rpy_rate, _ = np.split(full_state, [3, 7, 10, 13, 16, 19]) if self.QUAD_TYPE == QuadType.ONE_D: @@ -998,7 +1003,7 @@ def _get_observation(self): elif self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE: # {x, x_dot, z, z_dot, theta, theta_dot}. self.state = np.hstack( - [pos[0], vel[0], pos[2], vel[2], rpy[1], ang_v[1]] + [pos[0], vel[0], pos[2], vel[2], rpy[1], rpy_rate[1]] ).reshape((6,)) elif self.QUAD_TYPE == QuadType.TWO_D_ATTITUDE_5S: # {x, x_dot, z, z_dot, theta, theta_dot}. @@ -1021,18 +1026,17 @@ def _get_observation(self): # '[WARNING]: observation was clipped in Quadrotor._get_observation().' # ) - # Apply observation disturbance. - obs = deepcopy(self.state) - # Concatenate goal info (references state(s)) for RL. # Plus two because ctrl_step_counter has not incremented yet, and we want to return the obs (which would be # ctrl_step_counter + 1 as the action has already been applied), and the next state (+ 2) for the RL to see # the next state. + obs = deepcopy(self.state) if self.at_reset: obs = self.extend_obs(obs, 1) else: obs = self.extend_obs(obs, self.ctrl_step_counter + 2) + # Apply observation disturbance. if 'observation' in self.disturbances: obs = self.disturbances['observation'].apply(obs, self) return obs @@ -1046,7 +1050,7 @@ def _get_reward(self): # RL cost. if self.COST == Cost.RL_REWARD: state = self.state - act = np.asarray(self.current_noisy_physical_action) + act = np.asarray(self.current_clipped_action) act_error = act - self.U_GOAL # Quadratic costs w.r.t state and action # TODO: consider using multiple future goal states for cost in tracking diff --git a/safe_control_gym/experiments/train_rl_controller.py b/safe_control_gym/experiments/train_rl_controller.py index faaec7034..251f3d3a1 100644 --- a/safe_control_gym/experiments/train_rl_controller.py +++ b/safe_control_gym/experiments/train_rl_controller.py @@ -22,7 +22,6 @@ def train(): fac = ConfigFactory() config = fac.merge() config.algo_config['training'] = True - config.use_gpu = True shutil.rmtree(config.output_dir, ignore_errors=True) diff --git a/safe_control_gym/math_and_models/symbolic_systems.py b/safe_control_gym/math_and_models/symbolic_systems.py index 0bcc50f70..73919668b 100644 --- a/safe_control_gym/math_and_models/symbolic_systems.py +++ b/safe_control_gym/math_and_models/symbolic_systems.py @@ -3,7 +3,7 @@ import casadi as cs -class SymbolicModel(): +class SymbolicModel: '''Implements the dynamics model with symbolic variables. x_dot = f(x,u), y = g(x,u), with other pre-defined, symbolic functions