Skip to content

Commit

Permalink
fixed syntax errors
Browse files Browse the repository at this point in the history
  • Loading branch information
NeonCoal committed Jan 14, 2024
1 parent 859a77d commit 7ffef3c
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,14 @@ import org.team4099.lib.units.perSecond
class TelescopingArm(val io: TelescopingArmIO) : SubsystemBase() {
val inputs = TelescopingArmIO.TelescopingArmIOInputs()

val loadedFeedforward: ElevatorFeedforward = ElevatorFeedforward(
val loadedFeedForward: ElevatorFeedforward = ElevatorFeedforward(
TelescopingArmConstants.LOAD_KS.inVolts,
TelescopingArmConstants.LOAD_KG.inVolts,
(1.meters.perSecond * TelescopingArmConstants.LOAD_KV).inVolts,
(1.meters.perSecond.perSecond * TelescopingArmConstants.LOAD_KA).inVolts
)

val noLoadFeedforward: ElevatorFeedforward =
val noLoadFeedForward: ElevatorFeedforward =
ElevatorFeedforward(
TelescopingArmConstants.NO_LOAD_KS.inVolts,
TelescopingArmConstants.NO_LOAD_KG.inVolts,
Expand Down Expand Up @@ -69,7 +69,7 @@ class TelescopingArm(val io: TelescopingArmIO) : SubsystemBase() {
Logger.recordOutput("TelescopingArm/rightReverseLimitReached", rightReverseLimitReached)

if (kP.hasChanged() || kI.hasChanged() || kD.hasChanged()) {
io.configPID(kP.value, kI.value, kD.value)
io.configPID(kP.get(), kI.get(), kD.get())
}
}

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package com.team4099.robot2022.subsystems.climber
package com.team4099.robot2023.subsystems.TelescopingArm

import com.ctre.phoenix6.configs.TalonFXConfiguration
import com.revrobotics.CANSparkMax
Expand All @@ -13,7 +13,7 @@ import com.team4099.robot2023.subsystems.TelescopingArm.TelescopingArmIO
import org.team4099.lib.units.base.Length
import org.team4099.lib.units.sparkMaxLinearMechanismSensor

object TelescopingArmIOReal : TelescopingArmIO {
object TelescopingArmIONeo : TelescopingArmIO {
private val telescopingLeftArm: CANSparkMax = CANSparkMax(
Constants.TelescopingArm.L_ARM_ID,
CANSparkMaxLowLevel.MotorType.kBrushless
Expand Down

0 comments on commit 7ffef3c

Please sign in to comment.