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
# Matrices taken from somewhere, maybe TinyMPC, can't remember
Q=diag(MX([100, 100, 100, 0, 0, 0, 0, 0, 0, 0, 0, 0]))
R=diag(MX([10.0, 10.0, 10.0, 10.0]))

Test result:
# DEFAULT_DISCR_LEVEL = 50 -> Completely goes off rails at the beginning
  • Loading branch information
hedaniel7 committed Feb 16, 2024
1 parent 4520728 commit 357abf1
Showing 1 changed file with 5 additions and 4 deletions.
9 changes: 5 additions & 4 deletions gym_pybullet_drones/control/MPCCasADiControl.py
Original file line number Diff line number Diff line change
Expand Up @@ -171,14 +171,15 @@ def __init__(self,


# My own designed matrices partially inspired from TinyMPC
Q = diagcat(100, 100, 100, 1, 1, 1, 1, 1, 1, 1, 1, 1)
R = diagcat(10.0, 10.0, 10.0, 10.0)
#Q = diagcat(100, 100, 100, 1, 1, 1, 1, 1, 1, 1, 1, 1)
#R = diagcat(10.0, 10.0, 10.0, 10.0)
# DEFAULT_DISCR_LEVEL = 50 -> It seems to work, but looks too rigid and too slow


# Matrices taken from somewhere, maybe TinyMPC, can't remember
# Q=diag(MX([100, 100, 100, 0, 0, 0, 0, 0, 0, 0, 0, 0]))
# R=diag(MX([10.0, 10.0, 10.0, 10.0]))
Q=diag(MX([100, 100, 100, 0, 0, 0, 0, 0, 0, 0, 0, 0]))
R=diag(MX([10.0, 10.0, 10.0, 10.0]))
# DEFAULT_DISCR_LEVEL = 50 -> Completely goes off rails at the beginning

'''
Paper: Non-Linear Model Predictive Control Using CasADi Package for Trajectory Tracking of Quadrotor
Expand Down

0 comments on commit 357abf1

Please sign in to comment.