Skip to content

Commit

Permalink
pid variable adjustments
Browse files Browse the repository at this point in the history
  • Loading branch information
SirBeans committed Jan 29, 2024
1 parent af060f2 commit bdc5bcc
Show file tree
Hide file tree
Showing 6 changed files with 19 additions and 16 deletions.
10 changes: 5 additions & 5 deletions src/main/kotlin/com/team4099/robot2023/BuildConstants.kt
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,10 @@ package com.team4099.robot2023
const val MAVEN_GROUP = ""
const val MAVEN_NAME = "Crescendo-2024v2"
const val VERSION = "unspecified"
const val GIT_REVISION = 102
const val GIT_SHA = "604a3c944cf21d691d7f2d854357417009e237cd"
const val GIT_DATE = "2024-01-28T19:00:59Z"
const val GIT_REVISION = 103
const val GIT_SHA = "af060f29e117bcb356a8028ace24474cd3e9c484"
const val GIT_DATE = "2024-01-28T19:36:14Z"
const val GIT_BRANCH = "shooter"
const val BUILD_DATE = "2024-01-28T19:34:57Z"
const val BUILD_UNIX_TIME = 1706488497518L
const val BUILD_DATE = "2024-01-28T21:31:48Z"
const val BUILD_UNIX_TIME = 1706495508778L
const val DIRTY = 1
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ import org.team4099.lib.units.perSecond
object FlywheelConstants {
val LEFT_GEAR_RATIO = 1.0

val RIGHT_GEAR_RATIO = 24.0/48.0
val RIGHT_MOTOR_REVOLUTIONS_PER_FLYWHEEL_REVOLUTIONS = 48.0/24.0

val VOLTAGE_COMPENSATION = 12.volts

Expand All @@ -39,39 +39,39 @@ object FlywheelConstants {
val FLYWHEEL_TOLERANCE = 50.0.rotations.perMinute
object PID {
val RIGHT_REAL_KP: ProportionalGain<Velocity<Radian>, Volt> =
0.0.volts / 1.0.rotations.perMinute
0.01.volts / 1.0.rotations.perMinute
val RIGHT_REAL_KI: IntegralGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.rotations.perMinute * 1.0.seconds)
val RIGHT_REAL_KD: DerivativeGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.rotations.perMinute.perSecond)

val RIGHT_SIM_KP: ProportionalGain<Velocity<Radian>, Volt> =
0.0.volts / 1.0.rotations.perMinute
0.001.volts / 1.0.rotations.perMinute
val RIGHT_SIM_KI: IntegralGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.radians.perSecond * 1.0.seconds)
val RIGHT_SIM_KD: DerivativeGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.rotations.perMinute.perSecond)

val LEFT_REAL_KP: ProportionalGain<Velocity<Radian>, Volt> =
0.1.volts / 1.0.rotations.perMinute
0.01.volts / 1.0.rotations.perMinute
val LEFT_REAL_KI: IntegralGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.rotations.perMinute * 1.0.seconds)
val LEFT_REAL_KD: DerivativeGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.rotations.perMinute.perSecond)

val LEFT_SIM_KP: ProportionalGain<Velocity<Radian>, Volt> =
0.1.volts / 1.0.rotations.perMinute
0.01.volts / 1.0.rotations.perMinute
val LEFT_SIM_KI: IntegralGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.radians.perSecond * 1.0.seconds)
0.0.volts / (1.0.rotations.perSecond * 1.0.seconds)
val LEFT_SIM_KD: DerivativeGain<Velocity<Radian>, Volt> =
0.0.volts / (1.0.rotations.perMinute.perSecond)

val RIGHT_FLYWHEEL_KS = 0.001.volts
val RIGHT_FLYWHEEL_KV = 0.0075.volts / 1.radians.perSecond
val RIGHT_FLYWHEEL_KV = 0.0083.volts / 1.radians.perSecond
val RIGHT_FLYWHEEL_KA = 0.09.volts / 1.radians.perSecond.perSecond

val LEFT_FLYWHEEL_KS = 0.001.volts
val LEFT_FLYWHEEL_KV = 0.015.volts / 1.radians.perSecond
val LEFT_FLYWHEEL_KV = 0.02.volts / 1.radians.perSecond
val LEFT_FLYWHEEL_KA = 0.03.volts / 1.radians.perSecond.perSecond
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,9 @@ class Flywheel(val io: FlywheelIO) : SubsystemBase() {
FlywheelConstants.PID.LEFT_FLYWHEEL_KV,
FlywheelConstants.PID.LEFT_FLYWHEEL_KA
)
io.configPID(
rightkP.get(), rightkI.get(), rightkD.get(), leftkP.get(), leftkI.get(), leftkD.get()
)
}
override fun periodic() {
io.updateInputs(inputs)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ object FlywheelIOSim : FlywheelIO {
private val flywheelLeftSim: FlywheelSim =
FlywheelSim(
DCMotor.getFalcon500(2),
FlywheelConstants.RIGHT_GEAR_RATIO,
FlywheelConstants.RIGHT_MOTOR_REVOLUTIONS_PER_FLYWHEEL_REVOLUTIONS,
FlywheelConstants.INERTIA.inKilogramsMeterSquared
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ object FlywheelIOTalon : FlywheelIO {
private val flywheelRightSensor =
ctreAngularMechanismSensor(
flywheelRightTalon,
FlywheelConstants.RIGHT_GEAR_RATIO,
FlywheelConstants.RIGHT_MOTOR_REVOLUTIONS_PER_FLYWHEEL_REVOLUTIONS,
FlywheelConstants.VOLTAGE_COMPENSATION,
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ object WristIOTalon : WristIO {
private val wristSensor =
ctreAngularMechanismSensor(
wristTalon,
FlywheelConstants.RIGHT_GEAR_RATIO,
FlywheelConstants.RIGHT_MOTOR_REVOLUTIONS_PER_FLYWHEEL_REVOLUTIONS,
FlywheelConstants.VOLTAGE_COMPENSATION,
)

Expand Down

0 comments on commit bdc5bcc

Please sign in to comment.