From 967b5ff335080198ed061e9ce45a530637dc6458 Mon Sep 17 00:00:00 2001 From: John Joseph Date: Thu, 1 Feb 2024 10:18:01 -0500 Subject: [PATCH] Add encoders --- .../robot2024/subsystems/pivot/Pivot.kt | 8 +++++--- .../robot2024/subsystems/shooter/Shooter.kt | 18 ++++++++++++------ 2 files changed, 17 insertions(+), 9 deletions(-) diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/pivot/Pivot.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/pivot/Pivot.kt index 25cc040..2c63432 100644 --- a/src/main/kotlin/frc/team449/robot2024/subsystems/pivot/Pivot.kt +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/pivot/Pivot.kt @@ -104,9 +104,11 @@ open class Pivot( val motor = createSparkMax( "Shooter Right Motor", PivotConstants.MOTOR_ID, - NEOEncoder.creator( - PivotConstants.GEARING, - PivotConstants.UPR + encCreator = AbsoluteEncoder.creator( + PivotConstants.ENC_CHANNEL, + PivotConstants.OFFSET, + PivotConstants.UPR, + PivotConstants.ENC_INVERTED ), inverted = PivotConstants.INVERTED, currentLimit = PivotConstants.CURRENT_LIM, diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/Shooter.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/Shooter.kt index 907c6a0..865ab70 100644 --- a/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/Shooter.kt +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/Shooter.kt @@ -32,10 +32,10 @@ open class Shooter( ) : SubsystemBase() { open val rightVelocity: Supplier = - Supplier { rightMotor.velocity * ShooterConstants.UPR * ShooterConstants.GEARING } + Supplier { rightMotor.velocity } open val leftVelocity: Supplier = - Supplier { leftMotor.velocity * ShooterConstants.UPR * ShooterConstants.GEARING } + Supplier { leftMotor.velocity } init { this.defaultCommand = updateOnly() @@ -119,9 +119,12 @@ open class Shooter( val rightMotor = createSparkMax( "Shooter Right Motor", ShooterConstants.RIGHT_MOTOR_ID, - NEOEncoder.creator( + encCreator = QuadEncoder.creator( + Encoder(ShooterConstants.RIGHT_CHANNEL_A, ShooterConstants.RIGHT_CHANNEL_B), + ShooterConstants.CPR, + ShooterConstants.UPR, ShooterConstants.GEARING, - ShooterConstants.UPR + ShooterConstants.RIGHT_ENCODER_INVERTED ), inverted = ShooterConstants.RIGHT_MOTOR_INVERTED, currentLimit = ShooterConstants.CURRENT_LIMIT, @@ -130,9 +133,12 @@ open class Shooter( val leftMotor = createSparkMax( "Shooter Right Motor", ShooterConstants.LEFT_MOTOR_ID, - NEOEncoder.creator( + encCreator = QuadEncoder.creator( + Encoder(ShooterConstants.LEFT_CHANNEL_A, ShooterConstants.LEFT_CHANNEL_B), + ShooterConstants.CPR, + ShooterConstants.UPR, ShooterConstants.GEARING, - ShooterConstants.UPR + ShooterConstants.LEFT_ENCODER_INVERTED ), inverted = ShooterConstants.LEFT_MOTOR_INVERTED, currentLimit = ShooterConstants.CURRENT_LIMIT,