From c38a0e170210159e8e7d6d00a8236bdf44b282f0 Mon Sep 17 00:00:00 2001 From: Jeffery Date: Thu, 16 May 2024 14:54:32 -0400 Subject: [PATCH] updated characterization routine for krakens --- src/main/kotlin/frc/team449/robot2024/Robot.kt | 4 ++-- .../team449/robot2024/subsystems/ControllerBindings.kt | 9 +++------ .../robot2024/subsystems/shooter/SpinShooterKraken.kt | 10 +++++++++- 3 files changed, 14 insertions(+), 9 deletions(-) diff --git a/src/main/kotlin/frc/team449/robot2024/Robot.kt b/src/main/kotlin/frc/team449/robot2024/Robot.kt index 6ce4b21..30d44cc 100644 --- a/src/main/kotlin/frc/team449/robot2024/Robot.kt +++ b/src/main/kotlin/frc/team449/robot2024/Robot.kt @@ -12,7 +12,7 @@ import frc.team449.robot2024.subsystems.Climber.Companion.createClimber import frc.team449.robot2024.subsystems.Feeder.Companion.createFeeder import frc.team449.robot2024.subsystems.Undertaker.Companion.createUndertaker import frc.team449.robot2024.subsystems.pivot.Pivot.Companion.createPivot -import frc.team449.robot2024.subsystems.shooter.SpinShooter.Companion.createSpinShooter +import frc.team449.robot2024.subsystems.shooter.SpinShooterKraken.Companion.createKrakenSpinShooter import frc.team449.system.AHRS import frc.team449.system.light.Light.Companion.createLight import monologue.Annotations.Log @@ -49,7 +49,7 @@ class Robot : RobotBase(), Logged { val pivot = createPivot() @Log.NT - val shooter = createSpinShooter(this) + val shooter = createKrakenSpinShooter(this) @Log.NT val feeder = createFeeder() diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/ControllerBindings.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/ControllerBindings.kt index 7fa6193..e000358 100644 --- a/src/main/kotlin/frc/team449/robot2024/subsystems/ControllerBindings.kt +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/ControllerBindings.kt @@ -1,5 +1,6 @@ package frc.team449.robot2024.subsystems +import com.ctre.phoenix6.SignalLogger import edu.wpi.first.math.MathUtil import edu.wpi.first.math.geometry.Rotation2d import edu.wpi.first.units.Measure @@ -46,13 +47,9 @@ class ControllerBindings( Volts.of(0.5).per(Seconds.of(1.0)), Volts.of(3.0), Seconds.of(10.0) - ), + ) { state -> SignalLogger.writeString("state", state.toString()) }, Mechanism( - { voltage: Measure -> - run { - robot.shooter.setVoltage(voltage.`in`(Volts)) - } - }, + { voltage: Measure -> run { robot.shooter.setVoltage(voltage.`in`(Volts)) } }, null, robot.shooter, "shooter" diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/SpinShooterKraken.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/SpinShooterKraken.kt index f297610..c21a7dc 100644 --- a/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/SpinShooterKraken.kt +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/shooter/SpinShooterKraken.kt @@ -1,5 +1,6 @@ package frc.team449.robot2024.subsystems.shooter +import com.ctre.phoenix6.SignalLogger import com.ctre.phoenix6.configs.TalonFXConfiguration import com.ctre.phoenix6.controls.CoastOut import com.ctre.phoenix6.controls.VelocityVoltage @@ -44,6 +45,13 @@ open class SpinShooterKraken( private val rightRateLimiter = SlewRateLimiter(SpinShooterKrakenConstants.BRAKE_RATE_LIMIT) init { + name = "Kraken Spin Shooter" + + leftMotor.optimizeBusUtilization() + rightMotor.optimizeBusUtilization() + SignalLogger.setPath("/media/sda1/ctre-logs/") + SignalLogger.start() + this.defaultCommand = coast() } @@ -516,7 +524,7 @@ open class SpinShooterKraken( } companion object { - fun createSpinShooter(robot: Robot): SpinShooterKraken { + fun createKrakenSpinShooter(robot: Robot): SpinShooterKraken { val rightMotor = TalonFX(SpinShooterKrakenConstants.RIGHT_MOTOR_ID) val rightConfig = TalonFXConfiguration() rightConfig.CurrentLimits.StatorCurrentLimitEnable = true