Skip to content

Commit db4b7bc

Browse files
authored
Merge pull request #108 from strykeforce/2024-measures
2024 measures
2 parents f1bab35 + c53cd44 commit db4b7bc

File tree

4 files changed

+67
-3
lines changed

4 files changed

+67
-3
lines changed

build.gradle

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,12 +6,12 @@ plugins {
66
id "maven-publish"
77
id "org.jetbrains.kotlin.jvm" version "1.7.21"
88
id "com.google.devtools.ksp" version "1.7.21-1.0.8"
9-
id "edu.wpi.first.GradleRIO" version "2024.1.1"
9+
id "edu.wpi.first.GradleRIO" version "2024.2.1"
1010
id "com.diffplug.spotless" version "6.12.1"
1111
}
1212

1313
group = "org.strykeforce"
14-
version = "24.0.0"
14+
version = "24.0.1"
1515

1616
sourceCompatibility = JavaVersion.VERSION_17
1717
targetCompatibility = JavaVersion.VERSION_17

src/main/kotlin/org/strykeforce/telemetry/TelemetryService.kt

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,11 @@ package org.strykeforce.telemetry
44

55
import com.ctre.phoenix.motorcontrol.can.BaseTalon
66
import com.ctre.phoenix.motorcontrol.can.TalonSRX
7+
import com.ctre.phoenix6.hardware.CANcoder
78
import com.ctre.phoenix6.hardware.TalonFX
89
import mu.KotlinLogging
910
import org.strykeforce.telemetry.measurable.BaseTalonMeasurable
11+
import org.strykeforce.telemetry.measurable.CancoderMeasureable
1012
import org.strykeforce.telemetry.measurable.Measurable
1113
import org.strykeforce.telemetry.measurable.TalonSRXMeasurable
1214
import org.strykeforce.telemetry.talon.TalonFXFaultMeasureable
@@ -142,6 +144,16 @@ class TelemetryService(private val telemetryControllerFactory: Function<Inventor
142144
register(TalonFXMeasureable(talon))
143145
}
144146

147+
/**
148+
* Convenience method to register faults for a [com.ctre.phoenix6.hardware.CANcoder] for telemetry sending
149+
*
150+
* @param cancoder the CANcoder to register for data collection
151+
* @throws IllegalStateException if TelemetryService is running
152+
*/
153+
fun register(cancoder: CANcoder) {
154+
register(CancoderMeasureable(cancoder))
155+
}
156+
145157
/**
146158
* Get an unmodifiable view of the registered items.
147159
*
Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
package org.strykeforce.telemetry.measurable
2+
3+
import com.ctre.phoenix6.hardware.CANcoder
4+
import org.strykeforce.telemetry.talon.HAS_RESET_OCCURRED
5+
import org.strykeforce.telemetry.talon.IS_PRO_LIC
6+
7+
internal const val MAGNET_HEALTH = "MAGNET_HEALTH"
8+
//internal const val POSITION = "POSITION"
9+
internal const val POSITION_SINCE_BOOT = "POSITION_SINCE_BOOT"
10+
internal const val ABS_POSITION = "ABS_POSITION"
11+
internal const val SUPPLY_VOLTAGE = "SUPPLY_VOLTAGE"
12+
internal const val UNFILTERED_VELOCITY = "UNFILTERED_VELOCITY"
13+
internal const val VELOCITY = "VELOCITY"
14+
15+
16+
class CancoderMeasureable @JvmOverloads constructor(
17+
private val cancoder: CANcoder,
18+
override val description: String = "Cancoder ${cancoder.deviceID}"
19+
): Measurable {
20+
21+
override val deviceId = cancoder.deviceID
22+
override val measures = setOf(
23+
Measure(MAGNET_HEALTH, "Magnet Health") {cancoder.magnetHealth.valueAsDouble},
24+
Measure(POSITION, "Position") {cancoder.position.valueAsDouble},
25+
Measure(POSITION_SINCE_BOOT, "Position Since Boot") {cancoder.positionSinceBoot.valueAsDouble},
26+
Measure(ABS_POSITION, "Absolute Position") {cancoder.absolutePosition.valueAsDouble},
27+
Measure(SUPPLY_VOLTAGE, "Supply Voltage") {cancoder.supplyVoltage.valueAsDouble},
28+
Measure(UNFILTERED_VELOCITY, "Unfiltered Velocity") {cancoder.unfilteredVelocity.valueAsDouble},
29+
Measure(VELOCITY, "Velocity") {cancoder.velocity.valueAsDouble},
30+
Measure(IS_PRO_LIC, "Is Pro Licensed") {cancoder.isProLicensed.valueAsDouble},
31+
Measure(HAS_RESET_OCCURRED, "Has Reset Occurred") {cancoder.resetOccurredChecker.asBoolean.toDouble()}
32+
)
33+
}

src/main/kotlin/org/strykeforce/telemetry/measurable/TalonFXMeasureable.kt

Lines changed: 20 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,31 +4,41 @@ import com.ctre.phoenix6.hardware.TalonFX
44
import org.strykeforce.telemetry.measurable.Measurable
55
import org.strykeforce.telemetry.measurable.Measure
66
import org.strykeforce.telemetry.measurable.toDouble
7+
import kotlin.concurrent.timerTask
78

89
//Device Status
910
internal const val ACCELERATION = "ACCELERATION"
11+
internal const val ACCEL_SCALE = "ACCEL_SCALE"
1012
internal const val BRIDGE_OUTPUT = "BRIDGE_OUTPUT"
1113
internal const val DEVICE_TEMP = "DEVICE_TEMP"
1214
internal const val DIFF_AVG_POS = "DIFF_AVG_POS"
15+
internal const val DIFF_AVG_POS_SCALE = "DIFF_AVG_POS_SCALE"
1316
internal const val DIFF_AVG_VEL = "DIFF_AVG_VEL"
17+
internal const val DIFF_AVG_VEL_SCALE = "DIFF_AVG_VEL_SCALE"
1418
internal const val DIFF_DIFF_POS = "DIFF_DIFF_POS"
19+
internal const val DIFF_DIFF_POS_SCALE = "DIFF_DIFF_POS_SCALE"
1520
internal const val DIFF_DIFF_VEL = "DIFF_DIFF_VEL"
21+
internal const val DIFF_DIFF_VEL_SCALE = "DIFF_DIFF_VEL_SCALE"
1622
internal const val DUTY_CYCLE = "DUTY_CYCLE"
1723
internal const val FWD_LIM = "FWD_LIM"
1824
internal const val IS_PRO_LIC = "IS_PRO_LIC"
1925
internal const val IS_MM_RUNNING = "IS_MM_RUNNING"
2026
internal const val MOTOR_VOLTAGE = "MOTOR_VOLTAGE"
2127
internal const val POSITION = "POSITION"
28+
internal const val POS_SCALE = "POS_SCALE"
2229
internal const val PROCESSOR_TEMP = "PROCESSOR_TEMP"
2330
internal const val HAS_RESET_OCCURRED = "HAS_RESET_OCCURRED"
2431
internal const val REV_LIM = "REV_LIM"
2532
internal const val ROTOR_POS = "ROTOR_POS"
33+
internal const val ROTOR_POS_SCALE = "ROTOR_POS_SCALE"
2634
internal const val ROTOR_VEL = "ROTOR_VEL"
35+
internal const val ROTOR_VEL_SCALE = "ROTOR_VEL_SCALE"
2736
internal const val STATOR_CURRENT = "STATOR_CURRENT"
2837
internal const val SUPPLY_CURRENT = "SUPPLY_CURRENT"
2938
internal const val SUPPLY_VOLTAGE = "SUPPLY_VOLTAGE"
3039
internal const val TORQUE_CURRENT = "TORQUE_CURRENT"
3140
internal const val VELOCITY = "VELOCITY"
41+
internal const val VEL_SCALE = "VEL_SCALE"
3242

3343
//PID
3444
internal const val CLOSED_LOOP_D_OUTPUT = "CLOSED_LOOP_D_OUTPUT"
@@ -83,32 +93,41 @@ class TalonFXMeasureable @JvmOverloads constructor(
8393
override val description: String = "TalonFX ${talonFX.deviceID}"
8494
): Measurable {
8595

86-
96+
val scaleFactor = 1000.0;
8797
override val deviceId = talonFX.deviceID
8898
override val measures = setOf(
8999
Measure(ACCELERATION, "Acceleration") {talonFX.acceleration.valueAsDouble},
100+
Measure(ACCEL_SCALE, "Accel. scaled") {talonFX.acceleration.valueAsDouble * scaleFactor},
90101
Measure(BRIDGE_OUTPUT, "Bridge Output") {talonFX.bridgeOutput.valueAsDouble},
91102
Measure(DEVICE_TEMP, "Device Temperature C"){talonFX.deviceTemp.valueAsDouble},
92103
Measure(DIFF_AVG_POS, "Differential Avg Position") {talonFX.differentialAveragePosition.valueAsDouble},
104+
Measure(DIFF_AVG_POS_SCALE,"Diff Avg Pos scaled"){talonFX.differentialAveragePosition.valueAsDouble * scaleFactor},
93105
Measure(DIFF_AVG_VEL, "Differential Avg Velocity") {talonFX.differentialAverageVelocity.valueAsDouble},
106+
Measure(DIFF_AVG_VEL_SCALE, "Diff Avg Vel scaled"){talonFX.differentialAverageVelocity.valueAsDouble * scaleFactor},
94107
Measure(DIFF_DIFF_POS, "Differential Difference Position"){talonFX.differentialDifferencePosition.valueAsDouble},
108+
Measure(DIFF_DIFF_POS_SCALE, "Diff Diff Pos scaled"){talonFX.differentialDifferencePosition.valueAsDouble * scaleFactor},
95109
Measure(DIFF_DIFF_VEL, "Differential Difference Velocity"){talonFX.differentialDifferenceVelocity.valueAsDouble},
110+
Measure(DIFF_DIFF_VEL_SCALE, "Diff Diff Vel scale"){talonFX.differentialDifferenceVelocity.valueAsDouble * scaleFactor},
96111
Measure(DUTY_CYCLE, "Applied Duty Cycle"){talonFX.dutyCycle.value},
97112
Measure(FWD_LIM, "Forward Limit Switch Closed"){talonFX.forwardLimit.valueAsDouble},
98113
Measure(IS_PRO_LIC, "Is Pro Licensed"){talonFX.isProLicensed.valueAsDouble},
99114
Measure(IS_MM_RUNNING, "Motion Magic Running"){talonFX.motionMagicIsRunning.valueAsDouble},
100115
Measure(MOTOR_VOLTAGE, "Motor Voltage"){talonFX.motorVoltage.valueAsDouble},
101116
Measure(POSITION, "Position"){talonFX.position.valueAsDouble},
117+
Measure(POS_SCALE, "Pos. scaled"){talonFX.position.valueAsDouble * scaleFactor},
102118
Measure(PROCESSOR_TEMP, "Processor Temp"){talonFX.processorTemp.valueAsDouble},
103119
Measure(HAS_RESET_OCCURRED, "Has Reset Occurred"){talonFX.hasResetOccurred().toDouble()},
104120
Measure(REV_LIM, "Reverse Limit Switch Closed"){talonFX.reverseLimit.valueAsDouble},
105121
Measure(ROTOR_POS, "Rotor Position"){talonFX.rotorPosition.valueAsDouble},
122+
Measure(ROTOR_POS_SCALE, "Rotor Pos scaled"){ talonFX.rotorPosition.valueAsDouble * scaleFactor},
106123
Measure(ROTOR_VEL, "Rotor Velocity"){talonFX.rotorVelocity.valueAsDouble},
124+
Measure(ROTOR_VEL_SCALE, "Rotor Vel scaled"){talonFX.rotorVelocity.valueAsDouble * scaleFactor},
107125
Measure(STATOR_CURRENT, "Stator Current"){talonFX.statorCurrent.valueAsDouble},
108126
Measure(SUPPLY_CURRENT, "Supply Current"){talonFX.supplyCurrent.valueAsDouble},
109127
Measure(SUPPLY_VOLTAGE, "Supply Voltage"){talonFX.supplyVoltage.valueAsDouble},
110128
Measure(TORQUE_CURRENT, "Torque Current"){talonFX.torqueCurrent.valueAsDouble},
111129
Measure(VELOCITY, "Velocity"){talonFX.velocity.valueAsDouble},
130+
Measure(VEL_SCALE, "Vel. scaled"){talonFX.velocity.valueAsDouble * scaleFactor},
112131
Measure(IS_INVERTED, "Is Inverted"){talonFX.inverted.toDouble()},
113132

114133
Measure(CLOSED_LOOP_D_OUTPUT, "Closed Loop Derivative Output"){talonFX.closedLoopDerivativeOutput.valueAsDouble},

0 commit comments

Comments
 (0)