Skip to content

Commit ce6ec47

Browse files
authored
Merge pull request #163 from strykeforce/jhh/health-check
Update tests and reports
2 parents 9004ffb + b3ff32f commit ce6ec47

File tree

5 files changed

+63
-52
lines changed

5 files changed

+63
-52
lines changed

src/main/kotlin/frc/team2767/deepspace/command/HealthCheckCommand.kt

Lines changed: 24 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,6 @@ class HealthCheckCommand : Command() {
4646
}
4747

4848
timedTest {
49-
warmUp = 0.5
50-
duration = 2.0
5149
percentOutput = 0.75
5250
currentRange = 0.6..1.2
5351
speedRange = 1000..1100
@@ -91,9 +89,13 @@ class HealthCheckCommand : Command() {
9189

9290
positionTest {
9391
percentOutput = 0.2
94-
encoderTarget = 10_000
92+
93+
encoderChangeTarget = 10_000
94+
encoderGoodEnough = 500
9595
encoderTimeOutCount = 5000
96-
zeroGoodEnough = 1500
96+
97+
currentRange = 0.0..0.5
98+
speedRange = 500..600
9799
}
98100

99101
positionTalon {
@@ -109,9 +111,13 @@ class HealthCheckCommand : Command() {
109111

110112
positionTest {
111113
percentOutput = 0.2
112-
zeroGoodEnough = 200
113-
encoderTarget = 2500
114+
115+
encoderChangeTarget = 2500
116+
encoderGoodEnough = 200
114117
encoderTimeOutCount = 500
118+
119+
currentRange = 0.0..0.5
120+
speedRange = 500..600
115121
}
116122
}
117123

@@ -121,16 +127,24 @@ class HealthCheckCommand : Command() {
121127

122128
positionTest {
123129
percentOutput = 0.2
124-
zeroGoodEnough = 50
125-
encoderTarget = 3000
130+
131+
encoderChangeTarget = 3000
132+
encoderGoodEnough = 50
126133
encoderTimeOutCount = 500
134+
135+
currentRange = 0.0..0.5
136+
speedRange = 500..600
127137
}
128138

129139
positionTest {
130140
percentOutput = -0.2
131-
zeroGoodEnough = 50
132-
encoderTarget = 3000
141+
142+
encoderChangeTarget = 3000
143+
encoderGoodEnough = 50
133144
encoderTimeOutCount = 250
145+
146+
currentRange = 0.0..0.5
147+
speedRange = 500..600
134148
}
135149
}
136150

Lines changed: 25 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
package frc.team2767.deepspace.health
22

3-
import com.ctre.phoenix.motorcontrol.ControlMode
43
import com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput
54
import com.ctre.phoenix.motorcontrol.can.TalonSRX
5+
import edu.wpi.first.wpilibj.Timer
66
import frc.team2767.deepspace.health.TalonPositionTest.State.*
77
import kotlinx.html.TagConsumer
88
import kotlinx.html.td
@@ -17,16 +17,19 @@ private val logger = KotlinLogging.logger {}
1717
class 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
}

src/main/kotlin/frc/team2767/deepspace/health/TalonTimedTest.kt

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,12 +86,14 @@ class TalonTimedTest(private val group: TalonGroup) : Test, Reportable {
8686

8787
override fun reportRows(tagConsumer: TagConsumer<Appendable>) {
8888
group.talons.forEach {
89+
val current = talonCurrents[it]?.average() ?: 0.0
90+
val speed = talonSpeeds[it]?.average()?.toInt() ?: 0
8991
tagConsumer.tr {
9092
td { +"${it.deviceID}" }
9193
td { +"%.2f".format(percentOutput * 12.0) }
9294
td { +"%.2f".format(duration) }
93-
td { +"%.2f".format(talonCurrents[it]?.average()) }
94-
td { +"%.2f".format(talonSpeeds[it]?.average()) }
95+
td(classes = currentRange.statusOf(current)) { +"%.2f".format(current) }
96+
td(classes = speedRange.statusOf(speed)) { +"$speed" }
9597
}
9698
}
9799
}

src/main/kotlin/frc/team2767/deepspace/health/Test.kt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@ package frc.team2767.deepspace.health
22

33
import kotlinx.html.TagConsumer
44

5+
fun <T : Comparable<T>> ClosedRange<T>.statusOf(value: T): String = if (this.contains(value)) "pass" else "fail"
6+
57
interface Test {
68
var name: String
79
fun execute()

src/main/resources/healthcheck.css

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,4 +17,12 @@ th {
1717

1818
td {
1919
text-align: right;
20+
}
21+
22+
td.pass {
23+
background-color: white
24+
}
25+
26+
td.fail {
27+
background-color: #ffb6c1
2028
}

0 commit comments

Comments
 (0)