diff --git a/.gitignore b/.gitignore index bcd2e2090..31805cfd4 100644 --- a/.gitignore +++ b/.gitignore @@ -7,8 +7,8 @@ examples/mpsc/unsafe_rl_temp_data/ examples/pid/*data/ # experiments/mpsc/results* +experiments/mpsc/models/rl_models* # -Results/ results/ z_docstring.py TODOs.md @@ -158,6 +158,3 @@ dmypy.json *c_generated_code/ *acados_ocp*.json -gpmpc_update/ -temp -models/ diff --git a/examples/hpo/train_rl_model.sh b/examples/hpo/train_rl_model.sh index 40be21d03..b3799c67d 100755 --- a/examples/hpo/train_rl_model.sh +++ b/examples/hpo/train_rl_model.sh @@ -32,7 +32,7 @@ python ./hpo_experiment.py \ --overrides \ ./rl/${ALGO}/config_overrides/${SYS}/${ALGO}_${SYS}.yaml \ ./rl/config_overrides/${SYS}/${SYS}_${TASK}.yaml \ - --output_dir ./Results/${SYS}_${ALGO}_data/ \ + --output_dir ./results/${SYS}_${ALGO}_data/ \ --tag Test \ --opt_hps ./rl/${ALGO}/config_overrides/${SYS}/optimized_hyperparameters.yaml \ --task ${SYS} --seed 2 \ diff --git a/examples/rl/rl_experiment.sh b/examples/rl/rl_experiment.sh index 48a8f9c65..62d7a37b2 100755 --- a/examples/rl/rl_experiment.sh +++ b/examples/rl/rl_experiment.sh @@ -39,6 +39,6 @@ do task_config.task_info.ilqr_ref=False \ task_config.task_info.ilqr_traj_data='../lqr/ilqr_ref_traj.npy' \ task_config.noise_scale=${NS} -# --pretrain_path ./Results/Benchmark_data/ilqr_ref/${SYS}_${ALGO}_data/${SEED} +# --pretrain_path ./results/benchmark_data/ilqr_ref/${SYS}_${ALGO}_data/${SEED} done -#done \ No newline at end of file +#done diff --git a/examples/rl/train_rl_model.sh b/examples/rl/train_rl_model.sh index 8e74f590c..fddd121b1 100755 --- a/examples/rl/train_rl_model.sh +++ b/examples/rl/train_rl_model.sh @@ -54,7 +54,7 @@ do --overrides \ ./config_overrides/${SYS}/${ALGO}_${SYS}.yaml \ ./config_overrides/${SYS}/${SYS}_${TASK}.yaml \ - --output_dir ./Results/${EXP_NAME}/${SYS}_${ALGO}_data/${SEED}/ \ + --output_dir ./results/${EXP_NAME}/${SYS}_${ALGO}_data/${SEED}/ \ --seed ${SEED} \ --use_gpu \ --kv_overrides \ diff --git a/experiments/mpsc/config_overrides/nl_mpsc_quadrotor_2D_attitude.yaml b/experiments/mpsc/config_overrides/nl_mpsc_quadrotor_2D_attitude.yaml index 17d5d79d3..3df801790 100644 --- a/experiments/mpsc/config_overrides/nl_mpsc_quadrotor_2D_attitude.yaml +++ b/experiments/mpsc/config_overrides/nl_mpsc_quadrotor_2D_attitude.yaml @@ -26,5 +26,5 @@ sf_config: decay_factor: 0.85 # Softening - soften_constraints: False + soften_constraints: True slack_cost: 250 diff --git a/experiments/mpsc/config_overrides/quadrotor_2D_attitude_tracking.yaml b/experiments/mpsc/config_overrides/quadrotor_2D_attitude_tracking.yaml index bed6fac7c..c9081cab0 100644 --- a/experiments/mpsc/config_overrides/quadrotor_2D_attitude_tracking.yaml +++ b/experiments/mpsc/config_overrides/quadrotor_2D_attitude_tracking.yaml @@ -82,8 +82,8 @@ task_config: lower_bounds: [-0.9, -2, 0.55, -2, -0.75, -3] - constraint_form: default_constraint constrained_variable: input - upper_bounds: [0.58212, 0.7] - lower_bounds: [0.09702, -0.7] + upper_bounds: [0.58212, 0.4] + lower_bounds: [0.09702, -0.4] done_on_out_of_bound: True done_on_violation: False diff --git a/experiments/mpsc/mpsc_experiment.py b/experiments/mpsc/mpsc_experiment.py index e5f85e5f7..ff9d884ae 100644 --- a/experiments/mpsc/mpsc_experiment.py +++ b/experiments/mpsc/mpsc_experiment.py @@ -162,8 +162,9 @@ def run_multiple_models(plot, all_models): 'config': config, 'X_GOAL': X_GOAL} - with open(f'./results_mpsc/{model}.pkl', 'wb') as f: - pickle.dump(all_results, f) + if not plot: + with open(f'./results_mpsc/{model}.pkl', 'wb') as f: + pickle.dump(all_results, f) if __name__ == '__main__': diff --git a/safe_control_gym/safety_filters/mpsc/nl_mpsc.py b/safe_control_gym/safety_filters/mpsc/nl_mpsc.py index c82025d71..c9f9e199a 100644 --- a/safe_control_gym/safety_filters/mpsc/nl_mpsc.py +++ b/safe_control_gym/safety_filters/mpsc/nl_mpsc.py @@ -1003,9 +1003,6 @@ def setup_acados_optimizer(self): ocp.cost.Vu[nx:nx + nu, :] = np.eye(nu) ocp.cost.Vx_e = np.eye(nx) - ocp.model.cost_y_expr = cs.vertcat(model.x, model.u) - ocp.model.cost_y_expr_e = model.x - # Updated on each iteration ocp.cost.yref = np.concatenate((self.model.X_EQ, self.model.U_EQ)) ocp.cost.yref_e = self.model.X_EQ @@ -1021,11 +1018,12 @@ def setup_acados_optimizer(self): ocp.constraints.ug = np.zeros((self.p)) # Slack - ocp.constraints.Jsg = np.eye(self.p) - ocp.cost.Zu = np.array([500] * self.p) - ocp.cost.Zl = np.array([500] * self.p) - ocp.cost.zu = np.array([500] * self.p) - ocp.cost.zl = np.array([500] * self.p) + if self.soften_constraints: + ocp.constraints.Jsg = np.eye(self.p) + ocp.cost.Zu = self.slack_cost * np.ones(self.p) + ocp.cost.Zl = self.slack_cost * np.ones(self.p) + ocp.cost.zu = self.slack_cost * np.ones(self.p) + ocp.cost.zl = self.slack_cost * np.ones(self.p) # Options ocp.solver_options.qp_solver = 'FULL_CONDENSING_HPIPM'