-
Notifications
You must be signed in to change notification settings - Fork 3
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
a97c2a1
commit 300ca93
Showing
2 changed files
with
56 additions
and
1 deletion.
There are no files selected for viewing
8 changes: 8 additions & 0 deletions
8
src/main/kotlin/frc/team449/robot2024/constants/subsystem/FeederConstants.kt
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,4 +1,12 @@ | ||
package frc.team449.robot2024.constants.subsystem | ||
|
||
object FeederConstants { | ||
const val MOTOR_ID = 7 | ||
const val FOLLOLWER_ID = 55 | ||
const val FOLLOWER_INV = false | ||
const val INVERTED = true | ||
const val CURRENT_LIM = 15 | ||
|
||
const val FEEDER_VOLTAGE = 8.0 | ||
const val REVERSE_VOLTAGE = -5.0 | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,4 +1,51 @@ | ||
package frc.team449.robot2024.subsystems | ||
class Feeder { | ||
import edu.wpi.first.util.sendable.SendableBuilder | ||
import edu.wpi.first.wpilibj2.command.Command | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase | ||
import frc.team449.robot2024.constants.subsystem.FeederConstants | ||
import frc.team449.robot2024.constants.subsystem.IntakeConstants | ||
import frc.team449.system.encoder.NEOEncoder | ||
import frc.team449.system.motor.WrappedMotor | ||
import frc.team449.system.motor.createSparkMax | ||
class Feeder( | ||
private val motor: WrappedMotor | ||
) : SubsystemBase() { | ||
fun feed(): Command { | ||
return this.runOnce { | ||
motor.setVoltage(IntakeConstants.INTAKE_VOLTAGE) | ||
} | ||
} | ||
|
||
fun reverse(): Command { | ||
return this.runOnce { | ||
motor.setVoltage(IntakeConstants.REVERSE_VOLTAGE) | ||
} | ||
} | ||
|
||
fun stop(): Command { | ||
return this.runOnce { | ||
motor.stopMotor() | ||
} | ||
} | ||
override fun initSendable(builder: SendableBuilder) { | ||
builder.publishConstString("1.0", "Feeder Motor Voltages") | ||
builder.addDoubleProperty("1.1 Last Feeder Motor Voltage", { motor.lastVoltage }, null) | ||
} | ||
companion object { | ||
fun createIntake(): Feeder { | ||
val motor = createSparkMax( | ||
"Feeder Motor", | ||
FeederConstants.MOTOR_ID, | ||
NEOEncoder.creator( | ||
1.0, | ||
1.0 | ||
), | ||
inverted = FeederConstants.INVERTED, | ||
currentLimit = FeederConstants.CURRENT_LIM, | ||
slaveSparks = mapOf(Pair(FeederConstants.FOLLOLWER_ID, FeederConstants.FOLLOWER_INV)) | ||
) | ||
|
||
return Feeder(motor) | ||
} | ||
} | ||
} |