Skip to content

Commit

Permalink
style(thrust): Config matrix grid spacing
Browse files Browse the repository at this point in the history
  • Loading branch information
OrionOth committed Nov 17, 2023
1 parent 8bce7db commit 903bd0e
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions src/seahawk/seahawk_deck/thrust.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,12 @@ def __init__(self):
super().__init__('thrust')

self.motor_config = [
[0, 0, 0, 0, 0.7071, 0.7071, -0.7071, -0.7071],
[0, 0, 0, 0, -0.7071, 0.7071, -0.7071, 0.7071],
[1, 1, 1, 1, 0, 0, 0, 0],
[-.19, -.19, .19, .19, -.105, -.105, .105, .105],
[-.12, .12, -.12, .12, -.15, .15, -.15, .15],
[-.047,-.047,-.047, -.047, 0.038, 0.038, 0.038, 0.038]
[ 0, 0, 0, 0, 0.7071, 0.7071, -0.7071, -0.7071 ], # Fx
[ 0, 0, 0, 0, -0.7071, 0.7071, -0.7071, 0.7071 ], # Fy
[ 1, 1, 1, 1, 0, 0, 0, 0 ], # Fz
[ -0.19, -0.19, 0.19, 0.19, -0.105, -0.105, 0.105, 0.105 ], # Rx (mm)
[ -0.12, 0.12, -0.12, 0.12, -0.15, 0.15, -0.15, 0.15 ], # Ry (mm)
[ -0.047, -0.047, -0.047, -0.047, 0.038, 0.038, 0.038, 0.038 ], # Rz (mm)
]
self.inverse_config = np.linalg.pinv(self.motor_config, rcond=1e-15, hermitian=False)

Expand Down

0 comments on commit 903bd0e

Please sign in to comment.