Skip to content

Commit ca5f749

Browse files
committed
push
1 parent 2800fc1 commit ca5f749

File tree

7 files changed

+68
-54
lines changed

7 files changed

+68
-54
lines changed

src/main/kotlin/com/frcteam3636/bunnybots2025/Robot.kt

Lines changed: 32 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -283,42 +283,39 @@ object Robot : LoggedRobot() {
283283
controller.b().onTrue(Shooter.Pivot.setTarget(Target.PETTINGZOO))
284284
controller.y().onTrue(Shooter.Pivot.setTarget(Target.AIM))
285285

286-
if (Preferences.getBoolean("DeveloperMode", false)) {
287-
controllerDev.leftBumper().onTrue(Commands.runOnce(SignalLogger::start))
288-
controllerDev.rightBumper().onTrue(Commands.runOnce(SignalLogger::stop))
289-
290-
if (Preferences.getBoolean("DrivetrainTuningMode", false)) {
291-
controllerDev.y().whileTrue(Drivetrain.sysIdQuasistaticSpin(SysIdRoutine.Direction.kForward))
292-
controllerDev.a().whileTrue(Drivetrain.sysIdQuasistaticSpin(SysIdRoutine.Direction.kReverse))
293-
controllerDev.b().whileTrue(Drivetrain.sysIdDynamicSpin(SysIdRoutine.Direction.kForward))
294-
controllerDev.x().whileTrue(Drivetrain.sysIdDynamicSpin(SysIdRoutine.Direction.kReverse))
295-
296-
controllerDev.povUp().whileTrue(Drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kForward))
297-
controllerDev.povDown().whileTrue(Drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kReverse))
298-
controllerDev.povRight().whileTrue(Drivetrain.sysIdDynamic(SysIdRoutine.Direction.kForward))
299-
controllerDev.povLeft().whileTrue(Drivetrain.sysIdDynamic(SysIdRoutine.Direction.kReverse))
300-
} else if (Preferences.getBoolean("FlywheelTuningMode", false)) {
301-
controllerDev.y().whileTrue(Shooter.Flywheels.sysIdQuasistatic(SysIdRoutine.Direction.kForward))
302-
controllerDev.a().whileTrue(Shooter.Flywheels.sysIdQuasistatic(SysIdRoutine.Direction.kReverse))
303-
controllerDev.b().whileTrue(Shooter.Flywheels.sysIdDynamic(SysIdRoutine.Direction.kForward))
304-
controllerDev.x().whileTrue(Shooter.Flywheels.sysIdDynamic(SysIdRoutine.Direction.kReverse))
305-
}
306-
307-
controllerDev.rightTrigger()
308-
.onTrue(Shooter.Pivot.setTarget(Target.TUNING))
309-
.onFalse(Shooter.Pivot.setTarget(Target.STOWED))
310-
controllerDev.leftTrigger()
311-
.onTrue(Shooter.Pivot.setTarget(Target.AIM))
312-
.onFalse(Shooter.Pivot.setTarget(Target.STOWED))
313-
314-
joystickDev.button(1).whileTrue(Drivetrain.calculateWheelRadius())
286+
controllerDev.leftBumper().onTrue(Commands.runOnce(SignalLogger::start))
287+
controllerDev.rightBumper().onTrue(Commands.runOnce(SignalLogger::stop))
288+
289+
// controllerDev.y().whileTrue(Drivetrain.sysIdQuasistaticSpin(SysIdRoutine.Direction.kForward))
290+
// controllerDev.a().whileTrue(Drivetrain.sysIdQuasistaticSpin(SysIdRoutine.Direction.kReverse))
291+
// controllerDev.b().whileTrue(Drivetrain.sysIdDynamicSpin(SysIdRoutine.Direction.kForward))
292+
// controllerDev.x().whileTrue(Drivetrain.sysIdDynamicSpin(SysIdRoutine.Direction.kReverse))
293+
294+
// controllerDev.povUp().whileTrue(Drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kForward))
295+
// controllerDev.povDown().whileTrue(Drivetrain.sysIdQuasistatic(SysIdRoutine.Direction.kReverse))
296+
// controllerDev.povRight().whileTrue(Drivetrain.sysIdDynamic(SysIdRoutine.Direction.kForward))
297+
// controllerDev.povLeft().whileTrue(Drivetrain.sysIdDynamic(SysIdRoutine.Direction.kReverse))
298+
controllerDev.y().whileTrue(Shooter.Flywheels.sysIdQuasistatic(SysIdRoutine.Direction.kForward))
299+
controllerDev.a().whileTrue(Shooter.Flywheels.sysIdQuasistatic(SysIdRoutine.Direction.kReverse))
300+
controllerDev.b().whileTrue(Shooter.Flywheels.sysIdDynamic(SysIdRoutine.Direction.kForward))
301+
controllerDev.x().whileTrue(Shooter.Flywheels.sysIdDynamic(SysIdRoutine.Direction.kReverse))
302+
303+
304+
controllerDev.rightTrigger()
305+
.onTrue(Shooter.Pivot.setTarget(Target.TUNING))
306+
.onFalse(Shooter.Pivot.setTarget(Target.STOWED))
307+
controllerDev.leftTrigger()
308+
.onTrue(Shooter.Pivot.setTarget(Target.AIM))
309+
.onFalse(Shooter.Pivot.setTarget(Target.STOWED))
310+
311+
joystickDev.button(1).whileTrue(Drivetrain.calculateWheelRadius())
312+
313+
joystickDev.button(2).onTrue(
314+
Commands.runOnce({
315+
Drivetrain.zeroFull()
316+
})
317+
)
315318

316-
joystickDev.button(2).onTrue(
317-
Commands.runOnce({
318-
Drivetrain.zeroFull()
319-
})
320-
)
321-
}
322319
}
323320

324321
override fun disabledInit() {}

src/main/kotlin/com/frcteam3636/bunnybots2025/subsystems/drivetrain/DrivetrainIO.kt

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,9 @@ open class DrivetrainInputs {
2727
var gyroConnected = true
2828
var measuredStates = PerCorner.generate { SwerveModuleState() }
2929
var measuredPositions = PerCorner.generate { SwerveModulePosition() }
30-
var moduleTemperatures = PerCorner.generate {
31-
SwerveModuleTemperature(0.0.celsius, 0.0.celsius)
32-
}
30+
// var moduleTemperatures = PerCorner.generate {
31+
// SwerveModuleTemperature(0.0.celsius, 0.0.celsius)
32+
// }
3333
}
3434

3535
abstract class DrivetrainIO {
@@ -46,7 +46,7 @@ abstract class DrivetrainIO {
4646
inputs.gyroConnected = gyro.connected
4747
inputs.measuredStates = modules.map { it.state }
4848
inputs.measuredPositions = modules.map { it.position }
49-
inputs.moduleTemperatures = modules.map { it.temperatures }
49+
// inputs.moduleTemperatures = modules.map { it.temperatures }
5050
}
5151

5252
var desiredStates: PerCorner<SwerveModuleState>

src/main/kotlin/com/frcteam3636/bunnybots2025/subsystems/indexer/IndexerIO.kt

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,10 @@ import com.frcteam3636.bunnybots2025.SparkFlex
1010
import com.frcteam3636.bunnybots2025.utils.math.amps
1111
import com.frcteam3636.bunnybots2025.utils.math.celsius
1212
import com.frcteam3636.bunnybots2025.utils.math.rpm
13+
import com.revrobotics.spark.SparkBase
1314
import com.revrobotics.spark.SparkLowLevel
15+
import com.revrobotics.spark.config.SparkBaseConfig
16+
import com.revrobotics.spark.config.SparkFlexConfig
1417
import edu.wpi.first.math.system.plant.DCMotor
1518
import edu.wpi.first.math.system.plant.LinearSystemId
1619
import edu.wpi.first.units.Units.*
@@ -34,7 +37,11 @@ interface IndexerIO {
3437
}
3538

3639
class IndexerIOReal : IndexerIO {
37-
private var indexerMotor = SparkFlex(REVDeviceId.IndexerMotor, SparkLowLevel.MotorType.kBrushless)
40+
private var indexerMotor = SparkFlex(REVDeviceId.IndexerMotor, SparkLowLevel.MotorType.kBrushless).apply {
41+
configure(SparkFlexConfig().apply {
42+
inverted(false)
43+
}, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters)
44+
}
3845
// private var canRange = CANrange(CTREDeviceId.CANRangeIndexer).apply {
3946
// configurator.apply(
4047
// CANrangeConfiguration().apply {

src/main/kotlin/com/frcteam3636/bunnybots2025/subsystems/intake/Intake.kt

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ object Intake : Subsystem {
4343
Logger.recordOutput("Intake/Pivot/Mechanism", mechanism)
4444

4545
// the extra 5 degrees is to account for encoder noise
46-
if ((inputs.pivotPosition > 95.degrees || inputs.pivotPosition < (-50).degrees) && !inputs.pivotDisabled) {
46+
if ((inputs.pivotPosition > 120.degrees || inputs.pivotPosition < (-75).degrees) && !inputs.pivotDisabled && Robot.isEnabled) {
4747
io.disablePivot()
4848
pivotDisabledAlert.set(true)
4949
}
@@ -91,8 +91,8 @@ object Intake : Subsystem {
9191
)
9292

9393
enum class Position(val angle: Angle) {
94-
Stowed((-45).degrees),
95-
Deployed(90.degrees);
94+
Stowed((-30).degrees),
95+
Deployed(99.degrees);
9696
}
9797

9898
val signals: Array<BaseStatusSignal>

src/main/kotlin/com/frcteam3636/bunnybots2025/subsystems/intake/IntakeIO.kt

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,13 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration
66
import com.ctre.phoenix6.controls.MotionMagicVoltage
77
import com.ctre.phoenix6.controls.NeutralOut
88
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue
9+
import com.ctre.phoenix6.signals.InvertedValue
910
import com.ctre.phoenix6.signals.NeutralModeValue
1011
import com.frcteam3636.bunnybots2025.*
1112
import com.frcteam3636.bunnybots2025.utils.math.*
13+
import com.revrobotics.spark.SparkBase
1214
import com.revrobotics.spark.SparkLowLevel
15+
import com.revrobotics.spark.config.SparkFlexConfig
1316
import edu.wpi.first.math.numbers.N1
1417
import edu.wpi.first.math.numbers.N2
1518
import edu.wpi.first.math.system.LinearSystem
@@ -50,7 +53,11 @@ class IntakeIOReal : IntakeIO {
5053
private var pivotDisabled = false
5154
private var brakeModeEnabled = true
5255

53-
private var intakeMotor = SparkFlex(REVDeviceId.IntakeMotor, SparkLowLevel.MotorType.kBrushless)
56+
private var intakeMotor = SparkFlex(REVDeviceId.IntakeMotor, SparkLowLevel.MotorType.kBrushless).apply {
57+
configure(SparkFlexConfig().apply {
58+
inverted(true)
59+
}, SparkBase.ResetMode.kResetSafeParameters, SparkBase.PersistMode.kPersistParameters)
60+
}
5461
private var intakePivotMotor = TalonFX(CTREDeviceId.IntakePivotMotor).apply {
5562
configurator.apply(TalonFXConfiguration().apply {
5663
Slot0.apply {
@@ -69,6 +76,7 @@ class IntakeIOReal : IntakeIO {
6976
}
7077
MotorOutput.apply {
7178
NeutralMode = NeutralModeValue.Brake
79+
Inverted = InvertedValue.Clockwise_Positive
7280
}
7381
})
7482
}
@@ -137,11 +145,11 @@ class IntakeIOReal : IntakeIO {
137145
}
138146

139147
companion object Constants {
140-
val PID_GAINS = PIDGains(6.0, 0.0, 0.0)
141-
val PROFILE_CRUISE_VELOCITY = 0.0.degreesPerSecond
142-
val PROFILE_ACCELERATION = 0.0.degreesPerSecondPerSecond
148+
val PID_GAINS = PIDGains(25.0, 0.0, 0.0)
149+
val PROFILE_CRUISE_VELOCITY = 15.0.rotationsPerSecond
150+
val PROFILE_ACCELERATION = 2.5.rotationsPerSecondPerSecond
143151
const val PROFILE_JERK = 0.0
144-
const val ENCODER_MAGNET_OFFSET = 0.0
152+
const val ENCODER_MAGNET_OFFSET = -0.134521
145153
const val ENCODER_TO_PIVOT_GEAR_RATIO = 2.25
146154
const val MOTOR_TO_ENCODER_GEAR_RATIO = 4.0
147155
}

src/main/kotlin/com/frcteam3636/bunnybots2025/subsystems/shooter/PivotIO.kt

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@ import com.ctre.phoenix6.controls.MotionMagicVoltage
77
import com.ctre.phoenix6.controls.NeutralOut
88
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue
99
import com.ctre.phoenix6.signals.NeutralModeValue
10+
import com.ctre.phoenix6.signals.SensorDirectionValue
1011
import com.frcteam3636.bunnybots2025.CANcoder
1112
import com.frcteam3636.bunnybots2025.CTREDeviceId
1213
import com.frcteam3636.bunnybots2025.TalonFX
@@ -80,7 +81,8 @@ class PivotIOReal : PivotIO {
8081
shooterPivotMotor.optimizeBusUtilization()
8182
CANcoder(CTREDeviceId.ShooterPivotEncoder).apply {
8283
configurator.apply(CANcoderConfiguration().apply {
83-
MagnetSensor.MagnetOffset = MAGNET_OFFSET - HARDSTOP_OFFSET
84+
MagnetSensor.MagnetOffset = MAGNET_OFFSET + HARDSTOP_OFFSET
85+
MagnetSensor.SensorDirection = SensorDirectionValue.Clockwise_Positive
8486
})
8587
}
8688
}
@@ -130,14 +132,14 @@ class PivotIOReal : PivotIO {
130132
}
131133

132134
companion object Constants {
133-
private val PID_GAINS = PIDGains(6.0, 0.0, 0.0)
135+
private val PID_GAINS = PIDGains(62.0, 0.0, 0.0)
134136
private const val SENSOR_TO_MECHANISM_GEAR_RATIO = 1.0
135137
private const val ROTOR_TO_SENSOR_GEAR_RATIO = 37.25
136-
private const val MAGNET_OFFSET = 0.0
138+
private const val MAGNET_OFFSET = -0.191650390625
137139
private val HARDSTOP_OFFSET = 12.degrees.inRotations()
138-
val PROFILE_ACCELERATION = 5.0.degreesPerSecondPerSecond
140+
val PROFILE_ACCELERATION = 2.0.rotationsPerSecondPerSecond
139141
const val PROFILE_JERK = 0.0
140-
val PROFILE_VELOCITY = 5.0.degreesPerSecond
142+
val PROFILE_VELOCITY = 12.0.rotationsPerSecond
141143
}
142144
}
143145

src/main/kotlin/com/frcteam3636/bunnybots2025/subsystems/shooter/Shooter.kt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ object Shooter {
102102
Logger.processInputs("Shooter/Flywheels", inputs)
103103

104104
Logger.recordOutput("Shooter/Flywheels/Setpoint", setpoint)
105-
io.setVelocity(setpoint) // move this into commands?
105+
// io.setVelocity(setpoint) // move this into commands?
106106
}
107107

108108
fun idle(): Command =

0 commit comments

Comments
 (0)