Skip to content

Commit

Permalink
test: # Care only 62.5% less about and velocities and reference input…
Browse files Browse the repository at this point in the history
… of the drone

                    # Reference Weighting matrices from the paper
                    # Q = diagcat(1, 1, 1, 0.6, 0.6, 1, 0, 0, 0, 0, 0, 0)
                    # R = diagcat(0.3, 0.3, 0.3, 0.8)

        Q = diagcat(1, 1, 1, 0.375, 0.375, 0.625, 0, 0, 0, 0, 0, 0)
        R = diagcat(0.1875, 0.1875, 0.1875, 0.5)

        # N DISCR LEVEL: 10 -> performs slower than 50%

Added additional test tracks folder in the file
  • Loading branch information
hedaniel7 committed Feb 19, 2024
1 parent 9414999 commit 53a356d
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 5 deletions.
14 changes: 10 additions & 4 deletions gym_pybullet_drones/control/MPCCasADiControl.py
Original file line number Diff line number Diff line change
Expand Up @@ -386,17 +386,23 @@ def __init__(self,
R = diagcat(0, 0, 0, 0)
# -> Test result: Drone completely goes off the rails and crazyflie flies crazily and fails'''

# Care only 62.5% less about and velocities and reference input of the drone
'''# Care only 62.5% less about and velocities and reference input of the drone
# Reference Weighting matrices from the paper
# Q = diagcat(1, 1, 1, 0.6, 0.6, 1, 0, 0, 0, 0, 0, 0)
# R = diagcat(0.3, 0.3, 0.3, 0.8)
Q = diagcat(1, 1, 1, 0.375, 0.375, 0.625, 0, 0, 0, 0, 0, 0)
R = diagcat(0.1875, 0.1875, 0.1875, 0.5)
# DEFAULT_DISCR_LEVEL = 10 ->
# First track only
# COMPLETION TIME MEAN: 3.9583333333333335
# SUCCESS RATE: 1.0
# AVERAGE DEVIATION: 0.07690801583058962
# MAXIMUM DEVIATION: 0.14062837262156286 '''



'''# Care 2x less (or only 50%) about and velocities and reference input of the drone
# Care 2x less (or only 50%) about and velocities and reference input of the drone
# Reference Weighting matrices from the paper
# Q = diagcat(1, 1, 1, 0.6, 0.6, 1, 0, 0, 0, 0, 0, 0)
# R = diagcat(0.3, 0.3, 0.3, 0.8)
Expand All @@ -411,7 +417,7 @@ def __init__(self,
# COMPLETION TIME MEAN: 4.119791666666666
# SUCCESS RATE: 1.0
# AVERAGE DEVIATION: 0.09995147199727226
# MAXIMUM DEVIATION: 0.2386860064898518'''
# MAXIMUM DEVIATION: 0.2386860064898518

'''# Care (or only 42.5%) about and velocities and reference input of the drone
# Reference Weighting matrices from the paper
Expand Down
10 changes: 9 additions & 1 deletion runnables/test_suite_eval/pid_CasADiMPC_20tracks_testsuite.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,17 @@
DEFAULT_DURATION_SEC = 10
DEFAULT_OUTPUT_FOLDER = 'results'
DEFAULT_COLAB = False
DEFAULT_DISCR_LEVEL = 10
DEFAULT_DISCR_LEVEL = 25
# Original folder
DEFAULT_EVAL_SET = "./eval-v0_n-ctrl-points-3_n-tracks-20_2024-02-11_22:18:28_46929077-0248-4c6e-b2b1-da2afb13b2e2"

# Folder used for RL and the video
#DEFAULT_EVAL_SET = "./eval-v0_n-ctrl-points-3_n-tracks-200_2024-02-12_12:21:14_3115f5a9-bd48-4b63-9194-5eda43e1329d"

# Last track of this was used for the video
#DEFAULT_EVAL_SET = "./eval-v0_n-ctrl-points-10_n-tracks-200_2024-02-12_15:01:53_bdee17ed-07ad-4e26-8e68-fa0a5ca1318c"


from runnables.test_suite_eval.utils import compute_metrics_single

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

0 comments on commit 53a356d

Please sign in to comment.