Skip to content

Commit

Permalink
Finished IntakeIO
Browse files Browse the repository at this point in the history
  • Loading branch information
lakelandspark committed Jan 10, 2024
1 parent 6235082 commit 5424f29
Show file tree
Hide file tree
Showing 8 changed files with 391 additions and 25 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
package com.team4099.robot2023.config.constants

import org.team4099.lib.units.base.amps
import org.team4099.lib.units.derived.degrees
import org.team4099.lib.units.derived.volts

object IntakeConstants {
val VOLTAGE_COMPENSATION = 12.0.volts

// TODO: Add value for encoder offset
val ABSOLUTE_ENCODER_OFFSET = 0.0.degrees

// TODO: Change gear ratio according to robot
val ROLLER_CURRENT_LIMIT = 50.0.amps
val ARM_CURRENT_LIMIT = 50.0.amps
const val ROLLER_MOTOR_INVERTED = true
const val ARM_MOTOR_INVERTED = false
const val ROLLER_GEAR_RATIO = 36.0 / 18.0
const val ARM_GEAR_RATIO = ((60.0 / 12.0) * (80.0 / 18.0) * (32.0 / 16.0))
const val ARM_ENCODER_GEAR_RATIO = 36.0 / 18.0
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
package com.team4099.robot2023.subsystems.Shooter

class Shooter {
}
class Shooter
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
package com.team4099.robot2023.subsystems.TelescopingArm

class TelescopingArm {
}
class TelescopingArm
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package com.team4099.robot2023.subsystems.feeder

import edu.wpi.first.wpilibj2.command.SubsystemBase
class Feeder(val io: FeederIO) : SubsystemBase() {

}
class Feeder(val io: FeederIO) : SubsystemBase()
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
package com.team4099.robot2023.subsystems.feeder

interface FeederIO {
}
interface FeederIO
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
package com.team4099.robot2023.subsystems.intake

class Intake {
}
class Intake
124 changes: 109 additions & 15 deletions src/main/kotlin/com/team4099/robot2023/subsystems/intake/IntakeIO.kt
Original file line number Diff line number Diff line change
Expand Up @@ -6,33 +6,127 @@ import org.team4099.lib.units.base.amps
import org.team4099.lib.units.base.celsius
import org.team4099.lib.units.base.inAmperes
import org.team4099.lib.units.base.inCelsius
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.derived.Angle
import org.team4099.lib.units.derived.DerivativeGain
import org.team4099.lib.units.derived.ElectricalPotential
import org.team4099.lib.units.derived.IntegralGain
import org.team4099.lib.units.derived.ProportionalGain
import org.team4099.lib.units.derived.Radian
import org.team4099.lib.units.derived.Volt
import org.team4099.lib.units.derived.degrees
import org.team4099.lib.units.derived.inDegrees
import org.team4099.lib.units.derived.inVolts
import org.team4099.lib.units.derived.rotations
import org.team4099.lib.units.derived.volts
import org.team4099.lib.units.inDegreesPerSecond
import org.team4099.lib.units.inRotationsPerMinute
import org.team4099.lib.units.perMinute
import org.team4099.lib.units.perSecond

interface IntakeIO {
class IntakeIOInputs : LoggableInputs {
var rollerVelocity = 0.0.rotations.perMinute
class IntakeIOInputs : LoggableInputs {
var rollerVelocity = 0.0.rotations.perMinute
var rollerAppliedVoltage = 0.0.volts

var rollerAppliedVoltage = 0.0.volts
var rollerSupplyCurrent = 0.0.amps
var rollerStatorCurrent = 0.0.amps
var rollerTemp = 0.0.celsius
var rollerSupplyCurrent = 0.0.amps
var rollerStatorCurrent = 0.0.amps
var rollerTemp = 0.0.celsius

override fun toLog(table: LogTable?) {
table?.put("rollerVelocityRPM", rollerVelocity.inRotationsPerMinute)
var armPosition = 0.0.degrees
var armVelocity = 0.0.degrees.perSecond
var armAbsoluteEncoderPosition = 0.0.degrees

table?.put("rollerAppliedVoltage", rollerAppliedVoltage.inVolts)
var armAppliedVoltage = 0.0.volts
var armSupplyCurrent = 0.0.amps
var armStatorCurrent = 0.0.amps
var armTemp = 0.0.celsius

table?.put("rollerSupplyCurrentAmps", rollerSupplyCurrent.inAmperes)
override fun toLog(table: LogTable?) {
table?.put("armPositionDegrees", armPosition.inDegrees)
table?.put("armAbsoluteEncoderPositionDegrees", armAbsoluteEncoderPosition.inDegrees)
table?.put("armVelocityDegreesPerSec", armVelocity.inDegreesPerSecond)
table?.put("armAppliedVoltage", armAppliedVoltage.inVolts)
table?.put("armSupplyCurrentAmps", armSupplyCurrent.inAmperes)
table?.put("armStatorCurrentAmps", armStatorCurrent.inAmperes)
table?.put("armTempCelsius", armTemp.inCelsius)

table?.put("rollerStatorCurrentAmps", rollerStatorCurrent.inAmperes)
table?.put("rollerVelocityRPM", rollerVelocity.inRotationsPerMinute)
table?.put("rollerAppliedVoltage", rollerAppliedVoltage.inVolts)
table?.put("rollerSupplyCurrentAmps", rollerSupplyCurrent.inAmperes)
table?.put("rollerStatorCurrentAmps", rollerStatorCurrent.inAmperes)
table?.put("rollerTempCelsius", rollerTemp.inCelsius)
}

override fun fromLog(table: LogTable?) {
table?.get("armPositionDegrees", armPosition.inDegrees)?.let { armPosition = it.degrees }

table?.get("armAbsoluteEncoderPositionDegrees", armAbsoluteEncoderPosition.inDegrees)?.let {
armAbsoluteEncoderPosition = it.degrees
}

table?.get("armVelocityDegreesPerSec", armVelocity.inDegreesPerSecond)?.let {
armVelocity = it.degrees.perSecond
}

table?.get("armAppliedVoltage", armAppliedVoltage.inVolts)?.let {
armAppliedVoltage = it.volts
}

table?.get("armSupplyCurrentAmps", armSupplyCurrent.inAmperes)?.let {
armSupplyCurrent = it.amps
}

table?.get("armStatorCurrentAmps", armStatorCurrent.inAmperes)?.let {
armStatorCurrent = it.amps
}

table?.get("armTempCelsius", armTemp.inCelsius)?.let { armTemp = it.celsius }

table?.get("rollerVelocityRPM", rollerVelocity.inRotationsPerMinute)?.let {
rollerVelocity = it.rotations.perSecond
}

table?.get("rollerAppliedVoltage", rollerAppliedVoltage.inVolts)?.let {
rollerAppliedVoltage = it.volts
}

table?.put("rollerTempCelsius", rollerTemp.inCelsius)
}
table?.get("rollerSupplyCurrentAmps", rollerSupplyCurrent.inAmperes)?.let {
rollerSupplyCurrent = it.amps
}

table?.get("rollerStatorCurrentAmps", rollerStatorCurrent.inAmperes)?.let {
rollerStatorCurrent = it.amps
}

table?.get("rollerTempCelsius", rollerTemp.inCelsius)?.let { rollerTemp = it.celsius }
}
}
}

fun updateInputs(io: IntakeIOInputs) {}

fun setRollerVoltage(voltage: ElectricalPotential) {}

fun setArmVoltage(voltage: ElectricalPotential) {}

fun setArmPosition(armPosition: Angle, feedforward: ElectricalPotential) {}

/**
* Updates the PID constants using the implementation controller
*
* @param kP accounts for linear error
* @param kI accounts for integral error
* @param kD accounts for derivative error
*/
fun configPID(
kP: ProportionalGain<Radian, Volt>,
kI: IntegralGain<Radian, Volt>,
kD: DerivativeGain<Radian, Volt>
) {}

/** Sets the current encoder position to be the zero value */
fun zeroEncoder() {}

fun setRollerBrakeMode(brake: Boolean) {}

fun setArmBrakeMode(brake: Boolean)
}
Loading

0 comments on commit 5424f29

Please sign in to comment.