11package frc.team2767.deepspace.health
22
3- import com.ctre.phoenix.motorcontrol.ControlMode
43import com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput
54import com.ctre.phoenix.motorcontrol.can.TalonSRX
5+ import edu.wpi.first.wpilibj.Timer
66import frc.team2767.deepspace.health.TalonPositionTest.State.*
77import kotlinx.html.TagConsumer
88import kotlinx.html.td
@@ -17,16 +17,19 @@ private val logger = KotlinLogging.logger {}
1717class TalonPositionTest (private val group : TalonGroup ) : Test, Reportable {
1818 override var name = " position test"
1919 var percentOutput = 0.0
20+ var currentRange = 0.0 .. 0.0
21+ var speedRange = 0 .. 0
22+ var warmUp = 0.25
2023 var peakVoltage = 12.0
21- var zeroGoodEnough = 5
22- var zeroTimeOutCount = 50
23- var encoderTarget = 0
24+
25+ var encoderChangeTarget = 0
26+ var encoderGoodEnough = 5
2427 var encoderTimeOutCount = 0
25- var controlMode = ControlMode .MotionMagic
2628
2729 private var state = STARTING
30+ private var startTime = 0.0
2831 private var iteration = 0
29- private var passed = false
32+ private var startingPosition = 0
3033
3134 private lateinit var talon: TalonSRX
3235 private var currents = mutableListOf<Double >()
@@ -44,32 +47,24 @@ class TalonPositionTest(private val group: TalonGroup) : Test, Reportable {
4447 }
4548 logger.info { " $name starting" }
4649 talon = group.talons.first()
47- talon.set(controlMode, 0.0 )
48- state = ZEROING
50+ startingPosition = talon.selectedSensorPosition
51+ talon.set(PercentOutput , percentOutput)
52+ startTime = Timer .getFPGATimestamp()
53+ state = RUNNING
4954 }
5055
51- ZEROING -> {
52- if (talon.selectedSensorPosition.absoluteValue < zeroGoodEnough) {
53- logger.info { " successfully zeroed encoder" }
54- talon.set(PercentOutput , percentOutput)
55- iteration = 0
56- state = RUNNING
57- return
58- }
59- if (iteration++ > zeroTimeOutCount) {
60- logger.warn { " timed out waiting for encoder zero, encoder = ${talon.selectedSensorPosition} " }
61- state = STOPPED
62- }
56+ WARMING -> if (Timer .getFPGATimestamp() - startTime >= warmUp) {
57+ state = RUNNING
6358 }
6459
6560 RUNNING -> {
6661 currents.add(talon.outputCurrent)
6762 speeds.add(talon.selectedSensorVelocity)
6863
69- if (talon.selectedSensorPosition.absoluteValue > encoderTarget ) {
70- logger.info { " reached encoder target $encoderTarget " }
64+ if (( talon.selectedSensorPosition - startingPosition) .absoluteValue > encoderChangeTarget ) {
65+ logger.info { " reached encoder target $encoderChangeTarget " }
7166 talon.set(PercentOutput , 0.0 )
72- state = PASSED
67+ state = STOPPED
7368 return
7469 }
7570
@@ -80,17 +75,6 @@ class TalonPositionTest(private val group: TalonGroup) : Test, Reportable {
8075 }
8176 }
8277
83- PASSED -> {
84- passed = true
85- talon.set(controlMode, 0.0 )
86- state = RESETTING
87- }
88-
89- RESETTING -> {
90- if (talon.selectedSensorPosition.absoluteValue < zeroGoodEnough)
91- logger.info { " repositioned to zero, finishing test" }
92- state = STOPPED
93- }
9478
9579 STOPPED -> logger.info { " position test stopped" }
9680
@@ -112,22 +96,23 @@ class TalonPositionTest(private val group: TalonGroup) : Test, Reportable {
11296 }
11397
11498 override fun reportRows (tagConsumer : TagConsumer <Appendable >) {
99+ val current = currents.average()
100+ val speed = speeds.average().toInt()
101+
115102 tagConsumer.tr {
116103 td { + " ${talon.deviceID} " }
117104 td { + " %.1f" .format(percentOutput * peakVoltage) }
118- td { + " $encoderTarget " }
119- td { + " %.2f" .format(currents.average() ) }
120- td { + " %.2f " .format(speeds.average()) }
105+ td { + " $encoderChangeTarget " }
106+ td(classes = currentRange.statusOf(current)) { + " %.2f" .format(current ) }
107+ td(classes = speedRange.statusOf(speed)) { + " $speed " }
121108 }
122109 }
123110
124111 @Suppress(" unused" )
125112 private enum class State {
126113 STARTING ,
127- ZEROING ,
114+ WARMING ,
128115 RUNNING ,
129- PASSED ,
130- RESETTING ,
131116 STOPPED
132117 }
133118}
0 commit comments