This repository has been archived by the owner on Oct 27, 2021. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 41
/
data_analyzer.py
1419 lines (1202 loc) · 50.8 KB
/
data_analyzer.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# This GUI analyzes the data collected by the data logger. Support is
# provided for both feedforward and feedback analysis, as well as diagnostic
# plotting.
import json
import math
import os
import tkinter
from tkinter import *
from tkinter import filedialog
from tkinter import messagebox
import control as cnt
import frccontrol as frccnt
import matplotlib
# This fixes a crash on macOS Mojave by using the TkAgg backend
# https://stackoverflow.com/a/34109240
matplotlib.use("TkAgg")
from matplotlib import pyplot as plt
import numpy as np
import statsmodels.api as sm
from frc_characterization.utils import FloatEntry, IntEntry
from mpl_toolkits.mplot3d import Axes3D
class ProgramState:
def __init__(self, dir):
self.mainGUI = tkinter.Tk()
self.project_path = StringVar(self.mainGUI)
self.project_path.set(dir)
self.window_size = IntVar(self.mainGUI)
self.window_size.set(8)
self.motion_threshold = DoubleVar(self.mainGUI)
self.motion_threshold.set(0.2)
self.subset = StringVar(self.mainGUI)
self.subset.set("All Combined")
self.units = StringVar(self.mainGUI)
self.units.set("Feet")
self.wheel_diam = DoubleVar(self.mainGUI)
self.wheel_diam.set(".333")
self.track_width = DoubleVar(self.mainGUI)
self.track_width.set("N/A")
self.stored_data = None
self.quasi_forward_l = None
self.quasi_backward_l = None
self.step_forward_l = None
self.step_backward_l = None
self.quasi_forward_r = None
self.quasi_backward_r = None
self.step_forward_r = None
self.step_backward_r = None
self.ks = DoubleVar(self.mainGUI)
self.kv = DoubleVar(self.mainGUI)
self.ka = DoubleVar(self.mainGUI)
self.kcos = DoubleVar(self.mainGUI)
self.r_square = DoubleVar(self.mainGUI)
self.qp = DoubleVar(self.mainGUI)
self.qp.set(1)
self.qv = DoubleVar(self.mainGUI)
self.qv.set(1.5)
self.max_effort = DoubleVar(self.mainGUI)
self.max_effort.set(7)
self.period = DoubleVar(self.mainGUI)
self.period.set(0.02)
self.max_controller_output = DoubleVar(self.mainGUI)
self.max_controller_output.set(12)
self.controller_time_normalized = BooleanVar(self.mainGUI)
self.controller_time_normalized.set(True)
self.measurement_delay = DoubleVar(self.mainGUI)
self.measurement_delay.set(0)
self.gearing = DoubleVar(self.mainGUI)
self.gearing.set(1)
self.controller_type = StringVar(self.mainGUI)
self.controller_type.set("Onboard")
self.encoder_epr = IntVar(self.mainGUI)
self.encoder_epr.set(4096)
self.has_slave = BooleanVar(self.mainGUI)
self.has_slave.set(False)
self.slave_period = DoubleVar(self.mainGUI)
self.slave_period.set(0.01)
self.gain_units_preset = StringVar(self.mainGUI)
self.gain_units_preset.set("Default")
self.loop_type = StringVar(self.mainGUI)
self.loop_type.set("Velocity")
self.kp = DoubleVar(self.mainGUI)
self.kd = DoubleVar(self.mainGUI)
# Set up main window
def configure_gui(STATE):
def getFile():
dataFile = tkinter.filedialog.askopenfile(
parent=STATE.mainGUI,
mode="rb",
title="Choose the data file (.JSON)",
initialdir=STATE.project_path.get(),
)
fileEntry.configure(state="normal")
fileEntry.delete(0, END)
fileEntry.insert(0, dataFile.name)
fileEntry.configure(state="readonly")
try:
data = json.load(dataFile)
try:
# Transform the data into a numpy array to make it easier to use
# -> transpose it so we can deal with it in columns
for k in JSON_DATA_KEYS:
data[k] = np.array(data[k]).transpose()
STATE.stored_data = data
analyzeButton.configure(state="normal")
except Exception as e:
messagebox.showerror(
"Error!",
"The structure of the data JSON was not recognized.\n"
+ "Details\n"
+ repr(e),
)
return
except Exception as e:
messagebox.showerror(
"Error!",
"The JSON file could not be loaded.\n" + "Details:\n" + repr(e),
parent=STATE.mainGUI,
)
return
def runAnalysis():
(
STATE.quasi_forward_l,
STATE.quasi_backward_l,
STATE.step_forward_l,
STATE.step_backward_l,
STATE.quasi_forward_r,
STATE.quasi_backward_r,
STATE.step_forward_r,
STATE.step_backward_r,
) = prepare_data(STATE.stored_data, window=STATE.window_size.get(), STATE=STATE)
if (
STATE.quasi_forward_l is None
or STATE.quasi_backward_l is None
or STATE.step_forward_l is None
or STATE.step_backward_l is None
or STATE.quasi_forward_r is None
or STATE.quasi_backward_r is None
or STATE.step_forward_r is None
or STATE.step_backward_r is None
):
return
if STATE.subset.get() == "Forward Left":
ks, kv, ka, rsquare = calcFit(STATE.quasi_forward_l, STATE.step_forward_l)
elif STATE.subset.get() == "Forward Right":
ks, kv, ka, rsquare = calcFit(STATE.quasi_forward_r, STATE.step_forward_r)
elif STATE.subset.get() == "Backward Left":
ks, kv, ka, rsquare = calcFit(STATE.quasi_backward_l, STATE.step_backward_l)
elif STATE.subset.get() == "Backward Right":
ks, kv, ka, rsquare = calcFit(STATE.quasi_backward_r, STATE.step_backward_r)
elif STATE.subset.get() == "Forward Combined":
ks, kv, ka, rsquare = calcFit(
np.concatenate((STATE.quasi_forward_l, STATE.quasi_forward_r), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_forward_r), axis=1),
)
elif STATE.subset.get() == "Backward Combined":
ks, kv, ka, rsquare = calcFit(
np.concatenate(
(STATE.quasi_backward_l, STATE.quasi_backward_r), axis=1
),
np.concatenate((STATE.step_backward_l, STATE.step_backward_r), axis=1),
)
elif STATE.subset.get() == "Left Combined":
ks, kv, ka, rsquare = calcFit(
np.concatenate((STATE.quasi_forward_l, STATE.quasi_backward_l), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_backward_l), axis=1),
)
elif STATE.subset.get() == "Right Combined":
ks, kv, ka, rsquare = calcFit(
np.concatenate((STATE.quasi_forward_r, STATE.quasi_backward_r), axis=1),
np.concatenate((STATE.step_forward_r, STATE.step_backward_r), axis=1),
)
else:
ks, kv, ka, rsquare = calcFit(
np.concatenate(
(
STATE.quasi_forward_l,
STATE.quasi_forward_r,
STATE.quasi_backward_l,
STATE.quasi_backward_r,
),
axis=1,
),
np.concatenate(
(
STATE.step_forward_l,
STATE.step_forward_r,
STATE.step_backward_l,
STATE.step_backward_r,
),
axis=1,
),
)
STATE.ks.set(float("%.3g" % ks))
STATE.kv.set(float("%.3g" % kv))
STATE.ka.set(float("%.3g" % ka))
STATE.r_square.set(float("%.3g" % rsquare))
if "track-width" in STATE.stored_data:
STATE.track_width.set(calcTrackWidth(STATE.stored_data["track-width"]))
else:
STATE.track_width.set("N/A")
calcGains()
timePlotsButton.configure(state="normal")
voltPlotsButton.configure(state="normal")
fancyPlotButton.configure(state="normal")
calcGainsButton.configure(state="normal")
def plotTimeDomain():
if STATE.subset.get() == "Forward Left":
_plotTimeDomain("Forward Left", STATE.quasi_forward_l, STATE.step_forward_l)
elif STATE.subset.get() == "Forward Right":
_plotTimeDomain(
"Forward Right", STATE.quasi_forward_r, STATE.step_forward_r
)
elif STATE.subset.get() == "Backward Left":
_plotTimeDomain(
"Backward Left", STATE.quasi_backward_l, STATE.step_backward_l
)
elif STATE.subset.get() == "Backward Right":
_plotTimeDomain(
"Backward Right", STATE.quasi_backward_r, STATE.step_backward_r
)
elif STATE.subset.get() == "Forward Combined":
_plotTimeDomain(
"Forward Combined",
np.concatenate((STATE.quasi_forward_l, STATE.quasi_forward_r), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_forward_r), axis=1),
)
elif STATE.subset.get() == "Backward Combined":
_plotTimeDomain(
"Backward Combined",
np.concatenate(
(STATE.quasi_backward_l, STATE.quasi_backward_r), axis=1
),
np.concatenate((STATE.step_backward_l, STATE.step_backward_r), axis=1),
)
elif STATE.subset.get() == "Left Combined":
_plotTimeDomain(
"Left Combined",
np.concatenate((STATE.quasi_forward_l, STATE.quasi_backward_l), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_backward_l), axis=1),
)
elif STATE.subset.get() == "Right Combined":
_plotTimeDomain(
"Right Combined",
np.concatenate((STATE.quasi_forward_r, STATE.quasi_backward_r), axis=1),
np.concatenate((STATE.step_forward_r, STATE.step_backward_r), axis=1),
)
else:
_plotTimeDomain(
"All Combined",
np.concatenate(
(
STATE.quasi_forward_l,
STATE.quasi_forward_r,
STATE.quasi_backward_l,
STATE.quasi_backward_r,
),
axis=1,
),
np.concatenate(
(
STATE.step_forward_l,
STATE.step_forward_r,
STATE.step_backward_l,
STATE.step_backward_r,
),
axis=1,
),
)
def plotVoltageDomain():
if STATE.subset.get() == "Forward Left":
_plotVoltageDomain(
"Forward Left", STATE.quasi_forward_l, STATE.step_forward_l, STATE
),
elif STATE.subset.get() == "Forward Right":
_plotVoltageDomain(
"Forward Right", STATE.quasi_forward_r, STATE.step_forward_r, STATE
)
elif STATE.subset.get() == "Backward Left":
_plotVoltageDomain(
"Backward Left", STATE.quasi_backward_l, STATE.step_backward_l, STATE
)
elif STATE.subset.get() == "Backward Right":
_plotVoltageDomain(
"Backward Right", STATE.quasi_backward_r, STATE.step_backward_r, STATE
)
elif STATE.subset.get() == "Forward Combined":
_plotVoltageDomain(
"Forward Combined",
np.concatenate((STATE.quasi_forward_l, STATE.quasi_forward_r), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_forward_r), axis=1),
STATE,
)
elif STATE.subset.get() == "Backward Combined":
_plotVoltageDomain(
"Backward Combined",
np.concatenate(
(STATE.quasi_backward_l, STATE.quasi_backward_r), axis=1
),
np.concatenate((STATE.step_backward_l, STATE.step_backward_r), axis=1),
STATE,
)
elif STATE.subset.get() == "Left Combined":
_plotVoltageDomain(
"Left Combined",
np.concatenate((STATE.quasi_forward_l, STATE.quasi_backward_l), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_backward_l), axis=1),
STATE,
)
elif STATE.subset.get() == "Right Combined":
_plotVoltageDomain(
"Right Combined",
np.concatenate((STATE.quasi_forward_r, STATE.quasi_backward_r), axis=1),
np.concatenate((STATE.step_forward_r, STATE.step_backward_r), axis=1),
STATE,
)
else:
_plotVoltageDomain(
"All Combined",
np.concatenate(
(
STATE.quasi_forward_l,
STATE.quasi_forward_r,
STATE.quasi_backward_l,
STATE.quasi_backward_r,
),
axis=1,
),
np.concatenate(
(
STATE.step_forward_l,
STATE.step_forward_r,
STATE.step_backward_l,
STATE.step_backward_r,
),
axis=1,
),
STATE,
)
def plot3D():
if STATE.subset.get() == "Forward Left":
_plot3D("Forward Left", STATE.quasi_forward_l, STATE.step_forward_l, STATE)
elif STATE.subset.get() == "Forward Right":
_plot3D("Forward Right", STATE.quasi_forward_r, STATE.step_forward_r, STATE)
elif STATE.subset.get() == "Backward Left":
_plot3D(
"Backward Left", STATE.quasi_backward_l, STATE.step_backward_l, STATE
)
elif STATE.subset.get() == "Backward Right":
_plot3D(
"Backward Right", STATE.quasi_backward_r, STATE.step_backward_r, STATE
)
elif STATE.subset.get() == "Forward Combined":
_plot3D(
"Forward Combined",
np.concatenate((STATE.quasi_forward_l, STATE.quasi_forward_r), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_forward_r), axis=1),
STATE,
)
elif STATE.subset.get() == "Backward Combined":
_plot3D(
"Backward Combined",
np.concatenate(
(STATE.quasi_backward_l, STATE.quasi_backward_r), axis=1
),
np.concatenate((STATE.step_backward_l, STATE.step_backward_r), axis=1),
STATE,
)
elif STATE.subset.get() == "Left Combined":
_plot3D(
"Left Combined",
np.concatenate((STATE.quasi_forward_l, STATE.quasi_backward_l), axis=1),
np.concatenate((STATE.step_forward_l, STATE.step_backward_l), axis=1),
STATE,
)
elif STATE.subset.get() == "Right Combined":
_plot3D(
"Right Combined",
np.concatenate((STATE.quasi_forward_r, STATE.quasi_backward_r), axis=1),
np.concatenate((STATE.step_forward_r, STATE.step_backward_r), axis=1),
STATE,
)
else:
_plot3D(
"All Combined",
np.concatenate(
(
STATE.quasi_forward_l,
STATE.quasi_forward_r,
STATE.quasi_backward_l,
STATE.quasi_backward_r,
),
axis=1,
),
np.concatenate(
(
STATE.step_forward_l,
STATE.step_forward_r,
STATE.step_backward_l,
STATE.step_backward_r,
),
axis=1,
),
STATE,
)
def calcGains():
period = (
STATE.period.get()
if not STATE.has_slave.get()
else STATE.slave_period.get()
)
if STATE.loop_type.get() == "Position":
kp, kd = _calcGainsPos(
STATE.kv.get(),
STATE.ka.get(),
STATE.qp.get(),
STATE.qv.get(),
STATE.max_effort.get(),
period,
STATE.measurement_delay.get(),
)
else:
kp, kd = _calcGainsVel(
STATE.kv.get(),
STATE.ka.get(),
STATE.qv.get(),
STATE.max_effort.get(),
period,
STATE.measurement_delay.get(),
)
# Scale gains to output
kp = kp / 12 * STATE.max_controller_output.get()
kd = kd / 12 * STATE.max_controller_output.get()
# Rescale kD if not time-normalized
if not STATE.controller_time_normalized.get():
kd = kd / STATE.period.get()
# Get correct conversion factor for rotations
if STATE.units.get() == "Radians":
rotation = 2 * math.pi
elif STATE.units.get() == "Rotations":
rotation = 1
else:
rotation = STATE.wheel_diam.get() * math.pi
# Convert to controller-native units
if STATE.controller_type.get() == "Talon":
kp = kp * rotation / (STATE.encoder_epr.get() * STATE.gearing.get())
kd = kd * rotation / (STATE.encoder_epr.get() * STATE.gearing.get())
if STATE.loop_type.get() == "Velocity":
kp = kp * 10
STATE.kp.set(float("%.3g" % kp))
STATE.kd.set(float("%.3g" % kd))
def calcTrackWidth(table):
# Note that this assumes the gyro angle is not modded (i.e. on [0, +infinity)),
# and that a positive angle travels in the counter-clockwise direction
d_left = table[-1][R_ENCODER_P_COL] - table[0][R_ENCODER_P_COL]
d_right = table[-1][L_ENCODER_P_COL] - table[0][L_ENCODER_P_COL]
d_angle = table[-1][GYRO_ANGLE_COL] - table[0][GYRO_ANGLE_COL]
if d_angle == 0:
messagebox.showerror(
"Error!", "Change in gyro angle was 0... Is your gyro set up correctly?"
)
return 0.0
# The below comes from solving ω=(vr−vl)/2r for 2r
# Absolute values used to ensure the calculated value is always positive
# and to add robustness to sensor inversion
diameter = (abs(d_left) + abs(d_right)) / abs(d_angle)
return diameter
def presetGains(*args):
def setMeasurementDelay(delay):
STATE.measurement_delay.set(
0 if STATE.loop_type.get() == "Position" else delay
)
# A number of motor controllers use moving average filters; these are types of FIR filters.
# A moving average filter with a window size of N is a FIR filter with N taps.
# The average delay (in taps) of an arbitrary FIR filter with N taps is (N-1)/2.
# All of the delays below assume that 1 T takes 1 ms.
#
# Proof:
# N taps with delays of 0 .. N - 1 T
#
# average delay = (sum 0 .. N - 1) / N T
# = (sum 1 .. N - 1) / N T
#
# note: sum 1 .. n = n(n + 1) / 2
#
# = (N - 1)((N - 1) + 1) / (2N) T
# = (N - 1)N / (2N) T
# = (N - 1)/2 T
presets = {
"Default": lambda: (
STATE.max_controller_output.set(12),
STATE.period.set(0.02),
STATE.controller_time_normalized.set(True),
STATE.controller_type.set("Onboard"),
setMeasurementDelay(0),
),
"WPILib (2020-)": lambda: (
STATE.max_controller_output.set(12),
STATE.period.set(0.02),
STATE.controller_time_normalized.set(True),
STATE.controller_type.set("Onboard"),
# Note that the user will need to remember to set this if the onboard controller is getting delayed measurements.
setMeasurementDelay(0),
),
"WPILib (Pre-2020)": lambda: (
STATE.max_controller_output.set(1),
STATE.period.set(0.05),
STATE.controller_time_normalized.set(False),
STATE.controller_type.set("Onboard"),
# Note that the user will need to remember to set this if the onboard controller is getting delayed measurements.
setMeasurementDelay(0),
),
"Talon FX": lambda: (
STATE.max_controller_output.set(1),
STATE.period.set(0.001),
STATE.controller_time_normalized.set(True),
STATE.controller_type.set("Talon"),
# https://phoenix-documentation.readthedocs.io/en/latest/ch14_MCSensor.html#changing-velocity-measurement-parameters
# 100 ms sampling period + a moving average window size of 64 (i.e. a 64-tap FIR) = 100/2 ms + (64-1)/2 ms = 81.5 ms.
# See above for more info on moving average delays.
setMeasurementDelay(81.5),
),
"Talon SRX (2020-)": lambda: (
STATE.max_controller_output.set(1),
STATE.period.set(0.001),
STATE.controller_time_normalized.set(True),
STATE.controller_type.set("Talon"),
# https://phoenix-documentation.readthedocs.io/en/latest/ch14_MCSensor.html#changing-velocity-measurement-parameters
# 100 ms sampling period + a moving average window size of 64 (i.e. a 64-tap FIR) = 100/2 ms + (64-1)/2 ms = 81.5 ms.
# See above for more info on moving average delays.
setMeasurementDelay(81.5),
),
"Talon SRX (Pre-2020)": lambda: (
STATE.max_controller_output.set(1023),
STATE.period.set(0.001),
STATE.controller_time_normalized.set(False),
STATE.controller_type.set("Talon"),
# https://phoenix-documentation.readthedocs.io/en/latest/ch14_MCSensor.html#changing-velocity-measurement-parameters
# 100 ms sampling period + a moving average window size of 64 (i.e. a 64-tap FIR) = 100/2 ms + (64-1)/2 ms = 81.5 ms.
# See above for more info on moving average delays.
setMeasurementDelay(81.5),
),
"Spark MAX (brushless)": lambda: (
STATE.max_controller_output.set(1),
STATE.period.set(0.001),
STATE.controller_time_normalized.set(False),
STATE.controller_type.set("Spark"),
# According to a Rev employee on the FRC Discord the window size is 40 so delay = (40-1)/2 ms = 19.5 ms.
# See above for more info on moving average delays.
setMeasurementDelay(19.5),
),
"Spark MAX (brushed)": lambda: (
STATE.max_controller_output.set(1),
STATE.period.set(0.001),
STATE.controller_time_normalized.set(False),
STATE.controller_type.set("Spark"),
# https://www.revrobotics.com/content/sw/max/sw-docs/cpp/classrev_1_1_c_a_n_encoder.html#a7e6ce792bc0c0558fb944771df572e6a
# 64-tap FIR = (64-1)/2 ms = 31.5 ms delay.
# See above for more info on moving average delays.
setMeasurementDelay(31.5),
),
}
presets.get(STATE.gain_units_preset.get(), "Default")()
def enableOffboard(*args):
if STATE.controller_type.get() == "Onboard":
gearingEntry.configure(state="disabled")
eprEntry.configure(state="disabled")
hasSlave.configure(state="disabled")
slavePeriodEntry.configure(state="disabled")
elif STATE.controller_type.get() == "Talon":
gearingEntry.configure(state="normal")
eprEntry.configure(state="normal")
hasSlave.configure(state="normal")
if STATE.has_slave.get():
slavePeriodEntry.configure(state="normal")
else:
slavePeriodEntry.configure(state="disabled")
else:
gearingEntry.configure(state="disabled")
eprEntry.configure(state="disabled")
hasSlave.configure(state="normal")
if STATE.has_slave.get():
slavePeriodEntry.configure(state="normal")
else:
slavePeriodEntry.configure(state="disabled")
def enableWheelDiam(*args):
if (
STATE.units.get() == "Feet"
or STATE.units.get() == "Inches"
or STATE.units.get() == "Meters"
):
diamEntry.configure(state="normal")
else:
diamEntry.configure(state="disabled")
def enableErrorBounds(*args):
if STATE.loop_type.get() == "Position":
qPEntry.configure(state="normal")
else:
qPEntry.configure(state="disabled")
# TOP OF WINDOW (FILE SELECTION)
topFrame = Frame(STATE.mainGUI)
topFrame.grid(row=0, column=0, columnspan=4)
Button(topFrame, text="Select Data File", command=getFile).grid(
row=0, column=0, padx=4
)
fileEntry = Entry(topFrame, width=80)
fileEntry.grid(row=0, column=1, columnspan=3)
fileEntry.configure(state="readonly")
Label(topFrame, text="Units:", width=10).grid(row=0, column=4)
unitChoices = {"Feet", "Inches", "Meters", "Radians", "Rotations"}
unitsMenu = OptionMenu(topFrame, STATE.units, *sorted(unitChoices))
unitsMenu.configure(width=10)
unitsMenu.grid(row=0, column=5, sticky="ew")
STATE.units.trace_add("write", enableWheelDiam)
Label(topFrame, text="Wheel Diameter (units):", anchor="e").grid(
row=1, column=3, columnspan=2, sticky="ew"
)
diamEntry = FloatEntry(topFrame, textvariable=STATE.wheel_diam)
diamEntry.grid(row=1, column=5)
Label(topFrame, text="Subset:", width=15).grid(row=0, column=6)
subsets = {
"All Combined",
"Forward Left",
"Forward Right",
"Forward Combined",
"Backward Left",
"Backward Right",
"Backward Combined",
"Left Combined",
"Right Combined",
}
dirMenu = OptionMenu(topFrame, STATE.subset, *sorted(subsets))
dirMenu.configure(width=20)
dirMenu.grid(row=0, column=7)
for child in topFrame.winfo_children():
child.grid_configure(padx=1, pady=1)
# FEEDFORWARD ANALYSIS FRAME
ffFrame = Frame(STATE.mainGUI, bd=2, relief="groove")
ffFrame.grid(row=1, column=0, columnspan=3, sticky="ns")
Label(ffFrame, text="Feedforward Analysis").grid(row=0, column=0, columnspan=5)
analyzeButton = Button(
ffFrame, text="Analyze Data", command=runAnalysis, state="disabled"
)
analyzeButton.grid(row=1, column=0, sticky="ew")
timePlotsButton = Button(
ffFrame,
text="Time-Domain Diagnostics",
command=plotTimeDomain,
state="disabled",
)
timePlotsButton.grid(row=2, column=0, sticky="ew")
voltPlotsButton = Button(
ffFrame,
text="Voltage-Domain Diagnostics",
command=plotVoltageDomain,
state="disabled",
)
voltPlotsButton.grid(row=3, column=0, sticky="ew")
fancyPlotButton = Button(
ffFrame, text="3D Diagnostics", command=plot3D, state="disabled"
)
fancyPlotButton.grid(row=4, column=0, sticky="ew")
Label(ffFrame, text="Accel Window Size:", anchor="e").grid(
row=1, column=1, sticky="ew"
)
windowEntry = IntEntry(ffFrame, textvariable=STATE.window_size, width=5)
windowEntry.grid(row=1, column=2)
Label(ffFrame, text="Motion Threshold (units/s):", anchor="e").grid(
row=2, column=1, sticky="ew"
)
thresholdEntry = FloatEntry(ffFrame, textvariable=STATE.motion_threshold, width=5)
thresholdEntry.grid(row=2, column=2)
Label(ffFrame, text="kS:", anchor="e").grid(row=1, column=3, sticky="ew")
kSEntry = FloatEntry(ffFrame, textvariable=STATE.ks, width=10)
kSEntry.grid(row=1, column=4)
kSEntry.configure(state="readonly")
Label(ffFrame, text="kV:", anchor="e").grid(row=2, column=3, sticky="ew")
kVEntry = FloatEntry(ffFrame, textvariable=STATE.kv, width=10)
kVEntry.grid(row=2, column=4)
kVEntry.configure(state="readonly")
Label(ffFrame, text="kA:", anchor="e").grid(row=3, column=3, sticky="ew")
kAEntry = FloatEntry(ffFrame, textvariable=STATE.ka, width=10)
kAEntry.grid(row=3, column=4)
kAEntry.configure(state="readonly")
Label(ffFrame, text="r-squared:", anchor="e").grid(row=4, column=3, sticky="ew")
rSquareEntry = FloatEntry(ffFrame, textvariable=STATE.r_square, width=10)
rSquareEntry.grid(row=4, column=4)
rSquareEntry.configure(state="readonly")
Label(ffFrame, text="Track Width:", anchor="e").grid(row=5, column=3, sticky="ew")
trackWidthEntry = FloatEntry(ffFrame, textvariable=STATE.track_width, width=10)
trackWidthEntry.grid(row=5, column=4)
trackWidthEntry.configure(state="readonly")
for child in ffFrame.winfo_children():
child.grid_configure(padx=1, pady=1)
# FEEDBACK ANALYSIS FRAME
fbFrame = Frame(STATE.mainGUI, bd=2, relief="groove")
fbFrame.grid(row=1, column=3, columnspan=5)
Label(fbFrame, text="Feedback Analysis").grid(row=0, column=0, columnspan=5)
Label(fbFrame, text="Gain Settings Preset:", anchor="e").grid(
row=1, column=0, sticky="ew"
)
presetChoices = {
"Default",
"WPILib (2020-)",
"WPILib (Pre-2020)",
"Talon FX",
"Talon SRX (2020-)",
"Talon SRX (Pre-2020)",
"Spark MAX (brushless)",
"Spark MAX (brushed)",
}
presetMenu = OptionMenu(fbFrame, STATE.gain_units_preset, *sorted(presetChoices))
presetMenu.grid(row=1, column=1)
presetMenu.config(width=12)
STATE.gain_units_preset.trace_add("write", presetGains)
Label(fbFrame, text="Controller Period (s):", anchor="e").grid(
row=2, column=0, sticky="ew"
)
periodEntry = FloatEntry(fbFrame, textvariable=STATE.period, width=10)
periodEntry.grid(row=2, column=1)
Label(fbFrame, text="Max Controller Output:", anchor="e").grid(
row=3, column=0, sticky="ew"
)
controllerMaxEntry = FloatEntry(
fbFrame, textvariable=STATE.max_controller_output, width=10
)
controllerMaxEntry.grid(row=3, column=1)
Label(fbFrame, text="Time-Normalized Controller:", anchor="e").grid(
row=4, column=0, sticky="ew"
)
normalizedButton = Checkbutton(fbFrame, variable=STATE.controller_time_normalized)
normalizedButton.grid(row=4, column=1)
Label(fbFrame, text="Controller Type:", anchor="e").grid(
row=5, column=0, sticky="ew"
)
controllerTypes = {"Onboard", "Talon", "Spark"}
controllerTypeMenu = OptionMenu(
fbFrame, STATE.controller_type, *sorted(controllerTypes)
)
controllerTypeMenu.grid(row=5, column=1)
STATE.controller_type.trace_add("write", enableOffboard)
Label(fbFrame, text="Measurement delay (ms):", anchor="e").grid(
row=6, column=0, sticky="ew"
)
velocityDelay = FloatEntry(fbFrame, textvariable=STATE.measurement_delay, width=10)
velocityDelay.grid(row=6, column=1)
Label(fbFrame, text="Post-Encoder Gearing:", anchor="e").grid(
row=7, column=0, sticky="ew"
)
gearingEntry = FloatEntry(fbFrame, textvariable=STATE.gearing, width=10)
gearingEntry.configure(state="disabled")
gearingEntry.grid(row=7, column=1)
Label(fbFrame, text="Encoder EPR:", anchor="e").grid(row=8, column=0, sticky="ew")
eprEntry = IntEntry(fbFrame, textvariable=STATE.encoder_epr, width=10)
eprEntry.configure(state="disabled")
eprEntry.grid(row=8, column=1)
Label(fbFrame, text="Has Slave:", anchor="e").grid(row=9, column=0, sticky="ew")
hasSlave = Checkbutton(fbFrame, variable=STATE.has_slave)
hasSlave.grid(row=9, column=1)
hasSlave.configure(state="disabled")
STATE.has_slave.trace_add("write", enableOffboard)
Label(fbFrame, text="Slave Update Period (s):", anchor="e").grid(
row=10, column=0, sticky="ew"
)
slavePeriodEntry = FloatEntry(fbFrame, textvariable=STATE.slave_period, width=10)
slavePeriodEntry.grid(row=10, column=1)
slavePeriodEntry.configure(state="disabled")
Label(fbFrame, text="Max Acceptable Position Error (units):", anchor="e").grid(
row=1, column=2, columnspan=2, sticky="ew"
)
qPEntry = FloatEntry(fbFrame, textvariable=STATE.qp, width=10)
qPEntry.grid(row=1, column=4)
qPEntry.configure(state="disabled")
Label(fbFrame, text="Max Acceptable Velocity Error (units/s):", anchor="e").grid(
row=2, column=2, columnspan=2, sticky="ew"
)
qVEntry = FloatEntry(fbFrame, textvariable=STATE.qv, width=10)
qVEntry.grid(row=2, column=4)
Label(fbFrame, text="Max Acceptable Control Effort (V):", anchor="e").grid(
row=3, column=2, columnspan=2, sticky="ew"
)
effortEntry = FloatEntry(fbFrame, textvariable=STATE.max_effort, width=10)
effortEntry.grid(row=3, column=4)
Label(fbFrame, text="Loop Type:", anchor="e").grid(
row=4, column=2, columnspan=2, sticky="ew"
)
loopTypes = {"Position", "Velocity"}
loopTypeMenu = OptionMenu(fbFrame, STATE.loop_type, *sorted(loopTypes))
loopTypeMenu.configure(width=8)
loopTypeMenu.grid(row=4, column=4)
STATE.loop_type.trace_add("write", enableErrorBounds)
# We reset everything to the selected preset when the user changes the loop type
# This prevents people from forgetting to change measurement delays
STATE.loop_type.trace_add("write", presetGains)
Label(fbFrame, text="kV:", anchor="e").grid(row=5, column=2, sticky="ew")
kVFBEntry = FloatEntry(fbFrame, textvariable=STATE.kv, width=10)
kVFBEntry.grid(row=5, column=3)
Label(fbFrame, text="kA:", anchor="e").grid(row=6, column=2, sticky="ew")
kAFBEntry = FloatEntry(fbFrame, textvariable=STATE.ka, width=10)
kAFBEntry.grid(row=6, column=3)
calcGainsButton = Button(
fbFrame,
text="Calculate Optimal Controller Gains",
command=calcGains,
state="disabled",
)
calcGainsButton.grid(row=7, column=2, columnspan=3)
Label(fbFrame, text="kP:", anchor="e").grid(row=8, column=2, sticky="ew")
kPEntry = FloatEntry(
fbFrame, textvariable=STATE.kp, width=10, state="readonly"
).grid(row=8, column=3)
Label(fbFrame, text="kD:", anchor="e").grid(row=9, column=2, sticky="ew")
kDEntry = FloatEntry(
fbFrame, textvariable=STATE.kd, width=10, state="readonly"
).grid(row=9, column=3)
for child in fbFrame.winfo_children():
child.grid_configure(padx=1, pady=1)
#
# These parameters are used to indicate which column of data each parameter
# can be found at
#
columns = dict(
time=0,
battery=1,
autospeed=2,
l_volts=3,
r_volts=4,
l_encoder_pos=5,
r_encoder_pos=6,
l_encoder_vel=7,
r_encoder_vel=8,
gyro_angle=9,
)
# These are the indices of data stored in the json file
TIME_COL = columns["time"]
BATTERY_COL = columns["battery"]
AUTOSPEED_COL = columns["autospeed"]
L_VOLTS_COL = columns["l_volts"]
R_VOLTS_COL = columns["r_volts"]
L_ENCODER_P_COL = columns["l_encoder_pos"]
R_ENCODER_P_COL = columns["r_encoder_pos"]
L_ENCODER_V_COL = columns["l_encoder_vel"]
R_ENCODER_V_COL = columns["r_encoder_vel"]
GYRO_ANGLE_COL = columns["gyro_angle"]
# The are the indices of data returned from prepare_data function
PREPARED_TM_COL = 0
PREPARED_V_COL = 1
PREPARED_POS_COL = 2
PREPARED_VEL_COL = 3
PREPARED_ACC_COL = 4
PREPARED_MAX_COL = PREPARED_ACC_COL
JSON_DATA_KEYS = ["slow-forward", "slow-backward", "fast-forward", "fast-backward"]
# From 449's R script (note: R is 1-indexed)
def smoothDerivative(tm, value, n):
"""
:param tm: time column
:param value: Value to take the derivative of
:param n: smoothing parameter
"""
dlen = len(value)
dt = tm[n:dlen] - tm[: (dlen - n)]
x = (value[(n):dlen] - value[: (dlen - n)]) / dt
# pad to original length by adding zeros on either side
return np.pad(x, (int(np.ceil(n / 2.0)), int(np.floor(n / 2.0))), mode="constant")
def trim_quasi_testdata(data, STATE):
adata = np.abs(data)
truth = np.all(
[
adata[L_ENCODER_V_COL] > STATE.motion_threshold.get(),
adata[L_VOLTS_COL] > 0,
adata[R_ENCODER_V_COL] > STATE.motion_threshold.get(),
adata[R_VOLTS_COL] > 0,
],