Skip to content

Commit

Permalink
test: Tested MPC Controller with the following weighting matrices:
Browse files Browse the repository at this point in the history
# Care only 75% less about and velocities and reference input of the drone
Q = diagcat(1, 1, 1, 0.45, 0.45, 0.75, 0, 0, 0, 0, 0, 0)
R = diagcat(0.225, 0.225, 0.225, 0.6)

Test result:
# DEFAULT_DISCR_LEVEL = 30 -> Good, but still worse than Paper weights
        # 5%|▌         | 1/20 [02:10<41:15, 130.31s/it]
        # 10%|█         | 2/20 [04:11<37:31, 125.09s/it]
        # 15%|█▌        | 3/20 [06:41<38:39, 136.46s/it]
# DEFAULT_DISCR_LEVEL = 100 ->  Quite slow
        # 5%|▌         | 1/20 [04:23<1:23:31, 263.79s/it]
        # 10%|█         | 2/20 [07:45<1:08:12, 227.35s/it]
  • Loading branch information
hedaniel7 committed Feb 16, 2024
1 parent 587a1a6 commit 463f547
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 3 deletions.
27 changes: 25 additions & 2 deletions gym_pybullet_drones/control/MPCCasADiControl.py
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,13 @@ def __init__(self,
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)
# DEFAULT_DISCR_LEVEL = 30 ->
# First track: 5%|▌ | 1/20 [02:09<40:56, 129.26s/it]
#COMPLETION TIME MEAN: 15.638157894736842
#SUCCESS RATE: 0.95
#AVERAGE DEVIATION: 0.029817046088798104
#MAXIMUM DEVIATION: 0.06448328287707432
'''

Expand Down Expand Up @@ -243,7 +250,7 @@ def __init__(self,
# the last goal position (0,0,0) though'''


# Care 2x less about and velocities and reference input of the drone
'''# Care 2x 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)
Expand All @@ -253,7 +260,23 @@ def __init__(self,
# DEFAULT_DISCR_LEVEL = 50 -> Performs actually well and finishes tracks, but is less accurate at some situations
# and misses points and has to go back
# DEFAULT_DISCR_LEVEL = 100 -> Quite slow 5%|▌ | 1/20 [03:38<1:09:19, 218.93s/it]
# DEFAULT_DISCR_LEVEL = 100 -> Quite slow 5%|▌ | 1/20 [03:38<1:09:19, 218.93s/it]'''

# Care only 75% 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.45, 0.45, 0.75, 0, 0, 0, 0, 0, 0)
R = diagcat(0.225, 0.225, 0.225, 0.6)

# DEFAULT_DISCR_LEVEL = 30 -> Good, but still worse than Paper weights
# 5%|▌ | 1/20 [02:10<41:15, 130.31s/it]
# 10%|█ | 2/20 [04:11<37:31, 125.09s/it]
# 15%|█▌ | 3/20 [06:41<38:39, 136.46s/it]
# DEFAULT_DISCR_LEVEL = 100 -> Quite slow
# 5%|▌ | 1/20 [04:23<1:23:31, 263.79s/it]
# 10%|█ | 2/20 [07:45<1:08:12, 227.35s/it]

x_init = P[0:Nx]
g = X[:, 0] - P[0:Nx] # initial condition constraints
Expand Down
2 changes: 1 addition & 1 deletion runnables/test_suite_eval/pid.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@
DEFAULT_DURATION_SEC = 50
DEFAULT_OUTPUT_FOLDER = 'results'
DEFAULT_COLAB = False
DEFAULT_DISCR_LEVEL = 100
DEFAULT_DISCR_LEVEL = 30
DEFAULT_EVAL_SET = "./eval-v0_n-ctrl-points-3_n-tracks-20_2024-02-11_22:18:28_46929077-0248-4c6e-b2b1-da2afb13b2e2"

from runnables.test_suite_eval.utils import compute_metrics_single
Expand Down

0 comments on commit 463f547

Please sign in to comment.