Skip to content

Commit

Permalink
updated characterization routine for krakens
Browse files Browse the repository at this point in the history
  • Loading branch information
theKnightedBird committed May 16, 2024
1 parent 047acd4 commit c38a0e1
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 9 deletions.
4 changes: 2 additions & 2 deletions src/main/kotlin/frc/team449/robot2024/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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()
Expand Down
Original file line number Diff line number Diff line change
@@ -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
Expand Down Expand Up @@ -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<Voltage> ->
run {
robot.shooter.setVoltage(voltage.`in`(Volts))
}
},
{ voltage: Measure<Voltage> -> run { robot.shooter.setVoltage(voltage.`in`(Volts)) } },
null,
robot.shooter,
"shooter"
Expand Down
Original file line number Diff line number Diff line change
@@ -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
Expand Down Expand Up @@ -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()
}

Expand Down Expand Up @@ -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
Expand Down

0 comments on commit c38a0e1

Please sign in to comment.