1+ package org.strykeforce.telemetry.measurable
2+
3+ import com.ctre.phoenix6.hardware.Pigeon2
4+ import jdk.jfr.Description
5+
6+ // internal const val ROLL = "ROLL"
7+ // internal const val PITCH = "PITCH"
8+ // internal const val YAW = "YAW"
9+ internal const val QUATW = " QUAT_W"
10+ internal const val QUATX = " QUAT_X"
11+ internal const val QUATY = " QUAT_Y"
12+ internal const val QUATZ = " QUAT_Z"
13+ internal const val GRAV_X = " GRAV_X"
14+ internal const val GRAV_Y = " GRAV_Y"
15+ internal const val GRAV_Z = " GRAV_Z"
16+ internal const val TEMP = " TEMP"
17+ internal const val NO_MOT_EN = " NO_MOT_EN"
18+ internal const val NO_MOT_CNT = " NO_MOT_CNT"
19+ internal const val UP_TIME = " UP_TIME"
20+ internal const val ACCUM_X = " ACCUM_X"
21+ internal const val ACCUM_Y = " ACCUM_Y"
22+ internal const val ACCUM_Z = " ACCUM_Z"
23+ internal const val ANG_VEL_X = " ANG_VEL_X"
24+ internal const val ANG_VEL_Y = " ANG_VEL_Y"
25+ internal const val ANG_VEL_Z = " ANG_VEL_Z"
26+ internal const val ACCEL_X = " ACCEL_X"
27+ internal const val ACCEL_Y = " ACCEL_Y"
28+ internal const val ACCEL_Z = " ACCEL_Z"
29+ internal const val SUPPLY_V = " SUPPLY_V"
30+ internal const val ANG_VEL_WORLD_X = " ANG_VEL_WORLD_X"
31+ internal const val ANG_VEL_WORLD_Y = " ANG_VEL_WORLD_Y"
32+ internal const val ANG_VEL_WORLD_Z = " ANG_VEL_WORLD_Z"
33+ internal const val MAG_X = " MAG_X"
34+ internal const val MAG_Y = " MAG_Y"
35+ internal const val MAG_Z = " MAG_Z"
36+ internal const val IS_PRO = " IS_PRO"
37+ internal const val RATE = " RATE"
38+ // internal const val ANGLE = "ANGLE"
39+ internal const val ROTATION2D = " ROTATION2D"
40+ internal const val ROTATION3D = " ROTATION3D"
41+ class Pigeon2Measureable @JvmOverloads constructor(
42+ private val pigeon2 : Pigeon2 ,
43+ override val description : String = " Pigeon2 ${pigeon2.deviceID} "
44+ ): Measurable {
45+
46+ override val deviceId = pigeon2.deviceID
47+ override val measures = setOf (
48+ Measure (ROLL , " Roll" ) {pigeon2.roll.valueAsDouble},
49+ Measure (PITCH , " Pitch" ) {pigeon2.pitch.valueAsDouble},
50+ Measure (YAW , " Yaw" ) {pigeon2.yaw.valueAsDouble},
51+ Measure (QUATW , " Quat W" ) {pigeon2.quatW.valueAsDouble},
52+ Measure (QUATX , " Quat X" ) {pigeon2.quatX.valueAsDouble},
53+ Measure (QUATY , " Quat Y" ) {pigeon2.quatY.valueAsDouble},
54+ Measure (QUATZ , " Quat Z" ) {pigeon2.quatZ.valueAsDouble},
55+ Measure (GRAV_X , " Gravity X" ) {pigeon2.gravityVectorX.valueAsDouble},
56+ Measure (GRAV_Y , " Gravity Y" ) { pigeon2.gravityVectorY.valueAsDouble},
57+ Measure (GRAV_Z , " Gravity Z" ) { pigeon2.gravityVectorZ.valueAsDouble},
58+ Measure (TEMP , " Temperature" ) { pigeon2.temperature.valueAsDouble},
59+ Measure (NO_MOT_EN , " No Motion Enabled" ) { pigeon2.noMotionEnabled.valueAsDouble},
60+ Measure (NO_MOT_CNT , " No Motion Count" ) { pigeon2.noMotionCount.valueAsDouble},
61+ Measure (UP_TIME , " Up Time" ) { pigeon2.upTime.valueAsDouble},
62+ Measure (ACCUM_X , " Accumulator X" ) { pigeon2.accumGyroX.valueAsDouble},
63+ Measure (ACCUM_Y , " Accumulator Y" ) {pigeon2.accumGyroY.valueAsDouble},
64+ Measure (ACCUM_Z , " Accumulator Z" ) { pigeon2.accumGyroZ.valueAsDouble},
65+ Measure (ANG_VEL_X , " Angular Vel X" ) {pigeon2.angularVelocityXDevice.valueAsDouble},
66+ Measure (ANG_VEL_Y , " Angular Vel Y" ) {pigeon2.angularVelocityYDevice.valueAsDouble},
67+ Measure (ANG_VEL_Z , " Angular Vel Z" ) {pigeon2.angularVelocityZDevice.valueAsDouble},
68+ Measure (ACCEL_X , " Acceleration X" ) {pigeon2.accelerationX.valueAsDouble},
69+ Measure (ACCEL_Y , " Acceleration Y" ) {pigeon2.accelerationY.valueAsDouble},
70+ Measure (ACCEL_Z , " Acceleration Z" ) {pigeon2.accelerationZ.valueAsDouble},
71+ Measure (SUPPLY_V , " Supply Voltage" ) {pigeon2.supplyVoltage.valueAsDouble},
72+ Measure (ANG_VEL_WORLD_X , " Angular Vel World X" ) {pigeon2.angularVelocityXWorld.valueAsDouble},
73+ Measure (ANG_VEL_WORLD_Y , " Angular Vel World Y" ) {pigeon2.angularVelocityYWorld.valueAsDouble},
74+ Measure (ANG_VEL_WORLD_Z , " Angular Vel World Z" ) {pigeon2.angularVelocityZWorld.valueAsDouble},
75+ Measure (MAG_X , " Mag Field X" ) {pigeon2.magneticFieldX.valueAsDouble},
76+ Measure (MAG_Y , " Mag Field Y" ) {pigeon2.magneticFieldY.valueAsDouble},
77+ Measure (MAG_Z , " Mag Field Z" ) {pigeon2.magneticFieldZ.valueAsDouble},
78+ Measure (IS_PRO , " Is Pro Lic" ) {pigeon2.isProLicensed.valueAsDouble},
79+ Measure (RATE , " Rate" ) {pigeon2.rate},
80+ Measure (ANGLE , " Angle" ) {pigeon2.angle},
81+ Measure (ROTATION2D , " Rotation2d Deg" ) {pigeon2.rotation2d.degrees}
82+ )
83+
84+ override fun equals (other : Any? ): Boolean {
85+ if (this == = other) return true
86+ if (javaClass != other?.javaClass) return false
87+
88+ other as Pigeon2
89+ if (deviceId != other.deviceID) return false
90+ return true
91+ }
92+
93+ override fun hashCode () = deviceId
94+ }
0 commit comments