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 3x less about the reference input and velocities of the drone
Q = diagcat(1, 1, 1, 0.2, 0.2, 0.1666, 0, 0, 0, 0, 0, 0)
R = diagcat(0.1, 0.1, 0.1, 0.2666)

Test result:
# DEFAULT_DISCR_LEVEL = 10 -> goes off track after 3 points
# DEFAULT_DISCR_LEVEL = 30 -> finishes 1st track with lots of mistakes
# DEFAULT_DISCR_LEVEL = 50 -> Performs actually quite well with minor mistakes
# DEFAULT_DISCR_LEVEL = 100 -> Performs actually quite well, but goes off track midway
# DEFAULT_DISCR_LEVEL = 200 -> Performs actually quite well with minor mistakes. A little slower. Misses the last goal position (0,0,0) though

fix: Also found about multiplier mistake before. It was actually 6x less and not 3x
  • Loading branch information
hedaniel7 committed Feb 16, 2024
1 parent c157495 commit 00df752
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 4 deletions.
26 changes: 23 additions & 3 deletions gym_pybullet_drones/control/MPCCasADiControl.py
Original file line number Diff line number Diff line change
Expand Up @@ -200,18 +200,38 @@ def __init__(self,
R = diagcat(0, 0, 0, 0)
# -> Test result: Drone circles around a reference point indefinitely and doesn't reach it'''

# Care 3x less about and velocities and do not care about the reference input of the drone
'''# Care 6x (Correction: was 3x) less about and velocities and do not care about the reference input of the drone
Q = diagcat(1, 1, 1, 0.1, 0.1, 0.1666, 0, 0, 0, 0, 0, 0)
R = diagcat(0, 0, 0, 0)
# -> Test result:
# DEFAULT_DISCR_LEVEL = 10 -> goes off track after 1 point
# DEFAULT_DISCR_LEVEL = 20 -> goes off track after 2 points
# DEFAULT_DISCR_LEVEL = 30 -> goes off track after 7-8 points
# DEFAULT_DISCR_LEVEL = 40 -> goes off track after 4 points
# DEFAULT_DISCR_LEVEL = 50 -> goes off track after 4 points
# DEFAULT_DISCR_LEVEL = 50 -> goes off track after 4 points'''

# Care 3x 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)


#R = diagcat(0.1, 0.1, 0.1, 0.2666)
Q = diagcat(1, 1, 1, 0.1, 0.1, 0.1666, 0, 0, 0, 0, 0, 0) #!! Correction this is imbalanced weighting! This is 6x less
# It should be Q = diagcat(1, 1, 1, 0.2, 0.2, 0.1666, 0, 0, 0, 0, 0, 0)
R = diagcat(0.1, 0.1, 0.1, 0.2666) #
# DEFAULT_DISCR_LEVEL = 10 -> goes off track after 1 points
# DEFAULT_DISCR_LEVEL = 30 -> goes off track after 10 points
# DEFAULT_DISCR_LEVEL = 50 -> goes off track after 4 points

# Care 3x less about and velocities and reference input of the drone
Q = diagcat(1, 1, 1, 0.2, 0.2, 0.1666, 0, 0, 0, 0, 0, 0)
R = diagcat(0.1, 0.1, 0.1, 0.2666)
# DEFAULT_DISCR_LEVEL = 10 -> goes off track after 3 points
# DEFAULT_DISCR_LEVEL = 30 -> finishes 1st track with lots of mistakes
# DEFAULT_DISCR_LEVEL = 50 -> Performs actually quite well with minor mistakes
# DEFAULT_DISCR_LEVEL = 100 -> Performs actually quite well, but goes off track midway
# DEFAULT_DISCR_LEVEL = 200 -> Performs actually quite well with minor mistakes. A little slower. Misses
# the last goal position (0,0,0) though

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 = 50
DEFAULT_DISCR_LEVEL = 100
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 00df752

Please sign in to comment.