Skip to content

Commit 0c417e1

Browse files
committed
fix line endings
1 parent 8825a59 commit 0c417e1

File tree

9 files changed

+515
-515
lines changed

9 files changed

+515
-515
lines changed
Lines changed: 32 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -1,33 +1,33 @@
1-
package org.strykeforce.thirdcoast.device
2-
3-
import com.ctre.phoenix.sensors.PigeonIMU
4-
import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame
5-
import org.strykeforce.thirdcoast.telemetry.item.PigeonIMUItem
6-
import mu.KotlinLogging
7-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
8-
9-
private val logger = KotlinLogging.logger {}
10-
11-
private const val DEFAULT_TEMP_COMP = false
12-
13-
14-
class PigeonService(private val telemetryService: TelemetryService, factory: (id: Int) -> PigeonIMU) :
15-
AbstractDeviceService<PigeonIMU>(factory) {
16-
17-
val timeout = 10
18-
var tempCompensation = DEFAULT_TEMP_COMP
19-
20-
21-
override fun activate(ids: Collection<Int>): Set<Int> {
22-
val new = super.activate(ids)
23-
telemetryService.stop()
24-
active.forEach {telemetryService.register(PigeonIMUItem(it)) }
25-
active.forEach {
26-
it.setTemperatureCompensationDisable(tempCompensation)
27-
}
28-
29-
telemetryService.start()
30-
return new
31-
}
32-
1+
package org.strykeforce.thirdcoast.device
2+
3+
import com.ctre.phoenix.sensors.PigeonIMU
4+
import com.ctre.phoenix.sensors.PigeonIMU_StatusFrame
5+
import org.strykeforce.thirdcoast.telemetry.item.PigeonIMUItem
6+
import mu.KotlinLogging
7+
import org.strykeforce.thirdcoast.telemetry.TelemetryService
8+
9+
private val logger = KotlinLogging.logger {}
10+
11+
private const val DEFAULT_TEMP_COMP = false
12+
13+
14+
class PigeonService(private val telemetryService: TelemetryService, factory: (id: Int) -> PigeonIMU) :
15+
AbstractDeviceService<PigeonIMU>(factory) {
16+
17+
val timeout = 10
18+
var tempCompensation = DEFAULT_TEMP_COMP
19+
20+
21+
override fun activate(ids: Collection<Int>): Set<Int> {
22+
val new = super.activate(ids)
23+
telemetryService.stop()
24+
active.forEach {telemetryService.register(PigeonIMUItem(it)) }
25+
active.forEach {
26+
it.setTemperatureCompensationDisable(tempCompensation)
27+
}
28+
29+
telemetryService.start()
30+
return new
31+
}
32+
3333
}
Lines changed: 72 additions & 72 deletions
Original file line numberDiff line numberDiff line change
@@ -1,73 +1,73 @@
1-
package org.strykeforce.thirdcoast.device
2-
3-
import com.ctre.phoenix.motorcontrol.ControlMode
4-
import com.ctre.phoenix.motorcontrol.NeutralMode
5-
import com.ctre.phoenix.motorcontrol.StatusFrame
6-
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced
7-
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
8-
import com.ctre.phoenix.motorcontrol.can.TalonFX
9-
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration
10-
import mu.KotlinLogging
11-
import org.strykeforce.thirdcoast.telemetry.TelemetryService
12-
import java.lang.IllegalStateException
13-
import kotlin.math.log
14-
15-
private val logger = KotlinLogging.logger {}
16-
17-
private val CONTROL_MODE_DEFAULT = ControlMode.PercentOutput
18-
private const val ACTIVE_SLOT_DEFAULT = 0
19-
private val NEUTRAL_MODE_DEFAULT = NeutralMode.EEPROMSetting
20-
private const val VOLTAGE_COMPENSATION_ENABLED_DEFAULT = true
21-
private const val CURRENT_LIMIT_ENABLED_DEFAULT = false
22-
private const val SENSOR_PHASE_INVERTED_DEFAULT = false
23-
private const val OUTPUT_INVERTED_DEFAULT = false
24-
25-
26-
class TalonFxService(private val telemetryService: TelemetryService, factory: (id:Int) -> TalonFX ):
27-
AbstractDeviceService<TalonFX>(factory) {
28-
29-
val timeout = 10
30-
var dirty = true
31-
var neutralMode = NEUTRAL_MODE_DEFAULT
32-
var controlMode = CONTROL_MODE_DEFAULT
33-
var voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
34-
var sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
35-
var activeSlotIndex: Int = ACTIVE_SLOT_DEFAULT
36-
37-
var activeConfiguration = TalonFXConfiguration()
38-
get() {
39-
if(!dirty) return field
40-
active.firstOrNull()?.getAllConfigs(field,timeout)?: logger.debug("no active talon fx's, returning default config")
41-
dirty = false
42-
return field
43-
}
44-
45-
val activeSlot: SlotConfiguration
46-
get() = when(activeSlotIndex){
47-
0 -> activeConfiguration.slot0
48-
1 -> activeConfiguration.slot1
49-
2 -> activeConfiguration.slot2
50-
3 -> activeConfiguration.slot3
51-
else -> throw IllegalStateException("invalid slot: $activeSlotIndex")
52-
}
53-
54-
val outputInverted: Boolean
55-
get() = active.firstOrNull()?.inverted?: OUTPUT_INVERTED_DEFAULT
56-
57-
override fun activate(ids: Collection<Int>): Set<Int> {
58-
dirty = true
59-
60-
val new = super.activate(ids)
61-
telemetryService.stop()
62-
active.filter { new.contains(it.deviceID) }.forEach(){
63-
it.setNeutralMode(neutralMode)
64-
it.selectProfileSlot(activeSlotIndex,0)
65-
it.enableVoltageCompensation(voltageCompensation)
66-
it.setSensorPhase(sensorPhase)
67-
it.setInverted(OUTPUT_INVERTED_DEFAULT)
68-
telemetryService.register(it)
69-
}
70-
telemetryService.start()
71-
return new
72-
}
1+
package org.strykeforce.thirdcoast.device
2+
3+
import com.ctre.phoenix.motorcontrol.ControlMode
4+
import com.ctre.phoenix.motorcontrol.NeutralMode
5+
import com.ctre.phoenix.motorcontrol.StatusFrame
6+
import com.ctre.phoenix.motorcontrol.StatusFrameEnhanced
7+
import com.ctre.phoenix.motorcontrol.can.SlotConfiguration
8+
import com.ctre.phoenix.motorcontrol.can.TalonFX
9+
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration
10+
import mu.KotlinLogging
11+
import org.strykeforce.thirdcoast.telemetry.TelemetryService
12+
import java.lang.IllegalStateException
13+
import kotlin.math.log
14+
15+
private val logger = KotlinLogging.logger {}
16+
17+
private val CONTROL_MODE_DEFAULT = ControlMode.PercentOutput
18+
private const val ACTIVE_SLOT_DEFAULT = 0
19+
private val NEUTRAL_MODE_DEFAULT = NeutralMode.EEPROMSetting
20+
private const val VOLTAGE_COMPENSATION_ENABLED_DEFAULT = true
21+
private const val CURRENT_LIMIT_ENABLED_DEFAULT = false
22+
private const val SENSOR_PHASE_INVERTED_DEFAULT = false
23+
private const val OUTPUT_INVERTED_DEFAULT = false
24+
25+
26+
class TalonFxService(private val telemetryService: TelemetryService, factory: (id:Int) -> TalonFX ):
27+
AbstractDeviceService<TalonFX>(factory) {
28+
29+
val timeout = 10
30+
var dirty = true
31+
var neutralMode = NEUTRAL_MODE_DEFAULT
32+
var controlMode = CONTROL_MODE_DEFAULT
33+
var voltageCompensation = VOLTAGE_COMPENSATION_ENABLED_DEFAULT
34+
var sensorPhase = SENSOR_PHASE_INVERTED_DEFAULT
35+
var activeSlotIndex: Int = ACTIVE_SLOT_DEFAULT
36+
37+
var activeConfiguration = TalonFXConfiguration()
38+
get() {
39+
if(!dirty) return field
40+
active.firstOrNull()?.getAllConfigs(field,timeout)?: logger.debug("no active talon fx's, returning default config")
41+
dirty = false
42+
return field
43+
}
44+
45+
val activeSlot: SlotConfiguration
46+
get() = when(activeSlotIndex){
47+
0 -> activeConfiguration.slot0
48+
1 -> activeConfiguration.slot1
49+
2 -> activeConfiguration.slot2
50+
3 -> activeConfiguration.slot3
51+
else -> throw IllegalStateException("invalid slot: $activeSlotIndex")
52+
}
53+
54+
val outputInverted: Boolean
55+
get() = active.firstOrNull()?.inverted?: OUTPUT_INVERTED_DEFAULT
56+
57+
override fun activate(ids: Collection<Int>): Set<Int> {
58+
dirty = true
59+
60+
val new = super.activate(ids)
61+
telemetryService.stop()
62+
active.filter { new.contains(it.deviceID) }.forEach(){
63+
it.setNeutralMode(neutralMode)
64+
it.selectProfileSlot(activeSlotIndex,0)
65+
it.enableVoltageCompensation(voltageCompensation)
66+
it.setSensorPhase(sensorPhase)
67+
it.setInverted(OUTPUT_INVERTED_DEFAULT)
68+
telemetryService.register(it)
69+
}
70+
telemetryService.start()
71+
return new
72+
}
7373
}
Lines changed: 37 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -1,38 +1,38 @@
1-
package org.strykeforce.thirdcoast.gyro
2-
3-
import net.consensys.cava.toml.TomlTable
4-
import org.strykeforce.thirdcoast.command.AbstractParameter
5-
import org.strykeforce.thirdcoast.command.Command
6-
import org.strykeforce.thirdcoast.parseResource
7-
import org.strykeforce.thirdcoast.talon.TalonParameter
8-
9-
class PigeonParameter(command: Command, toml: TomlTable, val enum: PigeonParameter.Enum) : AbstractParameter(command, toml) {
10-
11-
enum class Enum {
12-
ACCUM_Z_ANGLE,
13-
FUSED_HEADING,
14-
TEMP_COMP_DISABLE,
15-
YAW,
16-
GENERAL_STATUS,
17-
SIX_DEG_STATUS,
18-
FUSED_STATUS,
19-
GYRO_ACCUM_STATUS,
20-
GEN_COMPASS_STATUS,
21-
GEN_ACCEL_STATUS,
22-
SIX_QUAT_STATUS,
23-
MAG_STATUS,
24-
BIAS_GYRO_STATUS,
25-
BIAS_MAG_STATUS,
26-
BIAS_ACCEL_STATUS,
27-
FACTORY_DEFAULT,
28-
}
29-
30-
companion object {
31-
private val tomlTable by lazy { parseResource("/pigeon.toml") }
32-
33-
fun create(command: Command, param: String): PigeonParameter {
34-
val toml = tomlTable.getTable(param) ?: throw java.lang.IllegalArgumentException("missing param: $param")
35-
return PigeonParameter(command, toml, Enum.valueOf(param))
36-
}
37-
}
1+
package org.strykeforce.thirdcoast.gyro
2+
3+
import net.consensys.cava.toml.TomlTable
4+
import org.strykeforce.thirdcoast.command.AbstractParameter
5+
import org.strykeforce.thirdcoast.command.Command
6+
import org.strykeforce.thirdcoast.parseResource
7+
import org.strykeforce.thirdcoast.talon.TalonParameter
8+
9+
class PigeonParameter(command: Command, toml: TomlTable, val enum: PigeonParameter.Enum) : AbstractParameter(command, toml) {
10+
11+
enum class Enum {
12+
ACCUM_Z_ANGLE,
13+
FUSED_HEADING,
14+
TEMP_COMP_DISABLE,
15+
YAW,
16+
GENERAL_STATUS,
17+
SIX_DEG_STATUS,
18+
FUSED_STATUS,
19+
GYRO_ACCUM_STATUS,
20+
GEN_COMPASS_STATUS,
21+
GEN_ACCEL_STATUS,
22+
SIX_QUAT_STATUS,
23+
MAG_STATUS,
24+
BIAS_GYRO_STATUS,
25+
BIAS_MAG_STATUS,
26+
BIAS_ACCEL_STATUS,
27+
FACTORY_DEFAULT,
28+
}
29+
30+
companion object {
31+
private val tomlTable by lazy { parseResource("/pigeon.toml") }
32+
33+
fun create(command: Command, param: String): PigeonParameter {
34+
val toml = tomlTable.getTable(param) ?: throw java.lang.IllegalArgumentException("missing param: $param")
35+
return PigeonParameter(command, toml, Enum.valueOf(param))
36+
}
37+
}
3838
}

0 commit comments

Comments
 (0)