Skip to content

Commit

Permalink
Merge pull request #105 from strykeforce/healthcheck-fix
Browse files Browse the repository at this point in the history
Update healthcheck JSON format
  • Loading branch information
jhh committed Apr 11, 2023
2 parents d6a2148 + 527f3b1 commit 1d887f6
Show file tree
Hide file tree
Showing 3 changed files with 148 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ import com.sun.net.httpserver.HttpServer
import mu.KotlinLogging
import org.strykeforce.healthcheck.HealthCheckCommand
import java.io.OutputStream
import java.lang.Exception
import java.net.InetSocketAddress

private val logger = KotlinLogging.logger {}
Expand All @@ -26,14 +27,21 @@ class ReportServer(private val healthCheck: RobotHealthCheck) {
}

createContext("/data") { httpExchange ->
val jsonVisitor = JsonVisitor()
jsonVisitor.visit(healthCheck)

httpExchange.responseHeaders.let { headers ->
headers["Content-Type"] = "application/json"
}
httpExchange.sendResponseHeaders(200, 0)
httpExchange.responseBody.use { jsonVisitor.sendHealthCheck(it) }

httpExchange.responseBody.use {
try {
val jsonVisitor = JsonVisitor(it)
jsonVisitor.visit(healthCheck)
} catch (e: Exception) {
logger.error(e) { "error creating healthcheck JSON report" }
}
}

}

start()
Expand All @@ -43,7 +51,9 @@ class ReportServer(private val healthCheck: RobotHealthCheck) {

}

class JsonVisitor : HealthCheckVisitor {
class JsonVisitor(outputStream: OutputStream) : HealthCheckVisitor {

private val writer = outputStream.bufferedWriter()

private val meta = mapOf(
"case" to StringBuilder(),
Expand All @@ -55,27 +65,26 @@ class JsonVisitor : HealthCheckVisitor {
"duration" to StringBuilder(),
)

private val data = mutableMapOf(
"msec_elapsed" to StringBuilder(),
"talon" to StringBuilder(),
"case" to StringBuilder(),
"voltage" to StringBuilder(),
"position" to StringBuilder(),
"speed" to StringBuilder(),
"supply_current" to StringBuilder(),
"stator_current" to StringBuilder(),
)

private var name = ""

private var metaIndex = 0
private var index = 0
private var isFirst = true

override fun visit(healthCheck: RobotHealthCheck) {
writer.write("{\"data\":[")
healthCheck.healthChecks.forEach { it.accept(this) }

// remove trailing commas, grr json
meta.values.forEach { it.deleteCharAt(it.lastIndex) }
data.values.forEach { it.deleteCharAt(it.lastIndex) }

writer.write("],\"meta\":{")
for ((i, key) in meta.keys.withIndex()) {
writer.write("\"$key\":{${meta[key]}}")
if (i < meta.size - 1) writer.write(",")
}
writer.write("}}")
writer.flush()
}

override fun visit(healthCheck: SubsystemHealthCheck) {
Expand All @@ -99,6 +108,17 @@ class JsonVisitor : HealthCheckVisitor {
meta.getValue("duration").append("\"${metaIndex}\":${healthCheck.duration},")
metaIndex++

val data = mapOf(
"msec_elapsed" to StringBuilder(),
"talon" to StringBuilder(),
"case" to StringBuilder(),
"voltage" to StringBuilder(),
"position" to StringBuilder(),
"speed" to StringBuilder(),
"supply_current" to StringBuilder(),
"stator_current" to StringBuilder(),
)

healthCheck.data.forEach { healthCheckData ->
healthCheckData.timestamp.forEachIndexed { i, v ->
data.getValue("msec_elapsed").append("\"${index + i}\":$v,")
Expand All @@ -112,24 +132,20 @@ class JsonVisitor : HealthCheckVisitor {
}
index += healthCheckData.timestamp.size
}
}

fun sendHealthCheck(os: OutputStream) {
val writer = os.writer()

writer.write("{\"meta\":{")
for ((i, key) in meta.keys.withIndex()) {
writer.write("\"$key\":{${meta[key]}}")
if (i < meta.size - 1) writer.write(",")
data.values.forEach { if (it.lastIndex > 0) it.deleteCharAt(it.lastIndex) }
if (isFirst) {
writer.write("{")
isFirst = false
} else {
writer.write(",{")
}

writer.write("},\"data\":{")
for ((i, key) in data.keys.withIndex()) {
writer.write("\"$key\":{${data[key]}}")
if (i < data.size - 1) writer.write(",")
}

writer.write("}}")
writer.flush()
writer.write("}")
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ interface HealthCheckVisitor {

class DumpVisitor : HealthCheckVisitor {

private val buffer = StringBuilder()
val buffer = StringBuilder()

private val logger = KotlinLogging.logger {}
override fun visit(healthCheck: RobotHealthCheck) {
Expand Down Expand Up @@ -41,7 +41,7 @@ class DumpVisitor : HealthCheckVisitor {
}

override fun visit(healthCheck: TalonHealthCheckCase) {
buffer.appendLine(" $healthCheck")
buffer.appendLine(" $healthCheck: ${healthCheck.data.size} measurements")
healthCheck.data.forEach {
buffer.appendLine(" talon ${it.id} avg. voltage = ${it.averageVoltage.format()} volts")
buffer.appendLine(" talon ${it.id} avg. speed = ${it.averageSpeed.format()} ticks/100ms")
Expand Down
102 changes: 102 additions & 0 deletions src/test/java/org/strykeforce/healthcheck/internal/JsonVisitorTest.kt
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
package org.strykeforce.healthcheck.internal

import com.ctre.phoenix.motorcontrol.can.BaseTalon
import org.junit.jupiter.api.Assertions.*
import org.junit.jupiter.api.Disabled
import org.junit.jupiter.api.Test
import org.mockito.kotlin.mock
import org.mockito.kotlin.whenever
import java.io.ByteArrayOutputStream

class JsonVisitorTest {

@Test
@Disabled
fun testJson() {
val os = ByteArrayOutputStream()
os.use {
val jsonVisitor = JsonVisitor(it)
jsonVisitor.visit(newRobotHealthCheck())
assertEquals("foo", it.toString())

}

}

@Test
@Disabled
fun testDump() {
val dumpVisitor = DumpVisitor()
dumpVisitor.visit(newRobotHealthCheck())
assertEquals("foo", dumpVisitor.buffer.toString())
}

@Test
@Disabled
fun `RobotHealthCheck contains correct data`() {
val robotHealthCheck = newRobotHealthCheck()
assertEquals(1, robotHealthCheck.healthChecks.size)
val subsystemHealthCheck = robotHealthCheck.healthChecks.first() as SubsystemHealthCheck
assertEquals(1, subsystemHealthCheck.healthChecks.size)
val talonHealthCheck = subsystemHealthCheck.healthChecks.first() as TalonHealthCheck
assertEquals(2, talonHealthCheck.healthChecks.size)
val talonHealthCheckCase = talonHealthCheck.healthChecks.first() as TalonHealthCheckCase
assertEquals(3, talonHealthCheckCase.data.size)
val data = talonHealthCheckCase.data.first()
assertEquals(33, data.deviceId)
assertEquals(20, data.timestamp.first())
assertEquals(3.0, data.voltage.first())
assertEquals(10_000.0, data.position.first())
assertEquals(5_000.0, data.speed.first())
assertEquals(0.75, data.supplyCurrent.first())
assertEquals(1.5, data.statorCurrent.first())
}
}


private fun newRobotHealthCheck(): RobotHealthCheck {

val talon = mock<BaseTalon>()
val case = 0
whenever(talon.deviceID).thenReturn(33)

val data1 = TalonHealthCheckData(0, talon).apply {
timestamp.add(20)
voltage.add(3.0)
position.add(10_000.0)
speed.add(5000.0)
supplyCurrent.add(0.75)
statorCurrent.add(1.5)
}
val data2 = TalonHealthCheckData(0, talon).apply {
timestamp.add(40)
voltage.add(3.1)
position.add(10_00.1)
speed.add(5000.1)
supplyCurrent.add(0.76)
statorCurrent.add(1.6)
}

val case1 = object : TalonHealthCheckCase(talon, false, "TestType", 1.0, 1_000) {
override val name = "Case 1"
override fun isRunning(elapsed: Long) = false
override fun setTalon(talon: BaseTalon) = Unit
}.apply {
data.add(data1)
data.add(data2)
}

val case2 = object : TalonHealthCheckCase(talon, false, "TestType", 1.0, 1_000) {
override val name = "Case 2"
override fun isRunning(elapsed: Long) = false
override fun setTalon(talon: BaseTalon) = Unit
}.apply {
data.add(data1)
data.add(data2)
}
val talonHealthCheck = object : TalonHealthCheck(talon, listOf(case1, case2)) {}


val subsystemHealthCheck = SubsystemHealthCheck("TestSubsystem", listOf(talonHealthCheck))
return RobotHealthCheck("RobotHealthCheck", listOf(subsystemHealthCheck))
}

0 comments on commit 1d887f6

Please sign in to comment.