Skip to content

Commit

Permalink
chore/quick stash: Some changes which I stash about how I tried to te…
Browse files Browse the repository at this point in the history
…st out the RL models
  • Loading branch information
hedaniel7 committed Feb 20, 2024
1 parent d5faaec commit f34737c
Show file tree
Hide file tree
Showing 5 changed files with 50 additions and 7 deletions.
4 changes: 3 additions & 1 deletion agents/test_policy.py
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,9 @@ def run_test(config: Configuration, env_factory: BaseFactory, eval_mode=False):
if not eval_mode:
test_env = env_factory.get_test_env_gui()
else:
test_env = env_factory.get_test_env_no_gui()
#test_env = env_factory.get_test_env_no_gui()
# Changed to GUI on
test_env = env_factory.get_test_env_gui()
test_env_nogui = env_factory.get_test_env_no_gui()

eval_res = test_simple_follower(
Expand Down
Binary file not shown.
Binary file not shown.
7 changes: 3 additions & 4 deletions gym_pybullet_drones/control/MPCCasADiControl.py
Original file line number Diff line number Diff line change
Expand Up @@ -493,6 +493,7 @@ def __init__(self,
R = diagcat(0.3, 0.3, 0.3, 0.8)
# -> Test result: Drone completely goes off the rails and crazyflie flies crazily and fails'''


x_init = P[0:Nx]
g = X[:, 0] - P[0:Nx] # initial condition constraints
h = 0.15
Expand All @@ -508,11 +509,9 @@ def __init__(self,
u_ref = DM([hovering_thrust, tau_phi_ref, tau_theta_ref, tau_psi_ref])

for k in range(Nhoriz - 1):

##Adaptive k-Weighting matrices approach
Q = (1 - (k * 1.0 / Nhoriz)) * Q
R = (1 - (k * 1.0 / Nhoriz)) * R

#Q = (1 - (k * 1.0 / Nhoriz)) * Q
#R = (1 - (k * 1.0 / Nhoriz)) * R
st_ref = P[Nx:2 * Nx]
st = X[:, k]
cont = U[:, k]
Expand Down
46 changes: 44 additions & 2 deletions runnables/test_suite_eval/C_trajectory_following.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,11 @@
RECORD_VIDEO = False
OUTPUT_FOLDER = 'checkpointed_models'
COLAB = False
DEFAULT_EVAL_SET_FOLDER = "/shared/d/master/ws23/UAV-lab/git_repos/RL-pybullets-cf/runnables/test_suite_eval/eval-v0_n-ctrl-points-3_n-tracks-20_2024-02-11_22:18:28_46929077-0248-4c6e-b2b1-da2afb13b2e2"
#DEFAULT_EVAL_SET_FOLDER = "/shared/d/master/ws23/UAV-lab/git_repos/RL-pybullets-cf/runnables/test_suite_eval/eval-v0_n-ctrl-points-3_n-tracks-20_2024-02-11_22:18:28_46929077-0248-4c6e-b2b1-da2afb13b2e2"

## aligned this to my computer (Daniel He)
DEFAULT_EVAL_SET_FOLDER = "/home/dan/Projects/RL-pybullets-cf/runnables/test_suite_eval/eval-v0_n-ctrl-points-3_n-tracks-20_2024-02-11_22:18:28_46929077-0248-4c6e-b2b1-da2afb13b2e2"

####################################

###### USUALLY NOT CHANGED #########
Expand All @@ -44,14 +48,52 @@
EPISODE_LEN_SEC = 50
####################################

###### HYPERPARAMS #################
'''###### Original HYPERPARAMS #################
WAYPOINT_BUFFER_SIZE = 2
K_P = 5
K_WP = 8
K_S = 0.05
MAX_REWARD_DISTANCE = 0.0
WAYPOINT_DIST_TOL = 0.05
DEFAULT_DISCR_LEVEL = 10
# Result 20 tracks
# SUCCESS RATE: 1.0
# AVERAGE MEAN DEVIATION: 0.07290511259032172
# AVERAGE MAX DEVIATION: 0.15248093381751945
# AVERAGE TIME UNTIL LANDING: 7.826666666666666
'''


'''###### HYPERPARAMS #################
WAYPOINT_BUFFER_SIZE = 2
K_P = 5
K_WP = 8
K_S = 0.05
MAX_REWARD_DISTANCE = 0.0001
WAYPOINT_DIST_TOL = 0.04
DEFAULT_DISCR_LEVEL = 10
# Result 20 tracks
# SUCCESS RATE: 0.3
# AVERAGE MEAN DEVIATION: 0.27309728400409955
# AVERAGE MAX DEVIATION: 0.5015007941869536
# AVERAGE TIME UNTIL LANDING: 24.61111111111111'''

###### HYPERPARAMS #################
WAYPOINT_BUFFER_SIZE = 3
K_P = 5
K_WP = 5
K_S = 0.05
MAX_REWARD_DISTANCE = 0.03
WAYPOINT_DIST_TOL = 0.031
DEFAULT_DISCR_LEVEL = 10

# Result 20 tracks
# SUCCESS RATE: 0.9
# AVERAGE MEAN DEVIATION: 0.117966844891097
# AVERAGE MAX DEVIATION: 0.22631146890221565
# AVERAGE TIME UNTIL LANDING: 11.844444444444443
####################################

def save_benchmark(benchmarks: Dict[str, float], file_path: str):
Expand Down

0 comments on commit f34737c

Please sign in to comment.