diff --git a/build.gradle b/build.gradle index ba2238c0..17663ff7 100644 --- a/build.gradle +++ b/build.gradle @@ -83,7 +83,7 @@ dependencies { simulationRelease wpi.sim.enableRelease() implementation 'org.jetbrains.kotlin:kotlin-test-junit5' - implementation 'com.github.team4099:FalconUtils:1.1.28' + implementation 'com.github.team4099:FalconUtils:1.1.29' implementation 'org.apache.commons:commons-collections4:4.0' implementation 'com.google.code.gson:gson:2.10.1' implementation "io.javalin:javalin:5.3.2" diff --git a/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt b/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt index 51816cb9..31cdaefc 100644 --- a/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt +++ b/src/main/kotlin/com/team4099/lib/phoenix6/PositionVoltage.kt @@ -12,14 +12,14 @@ import org.team4099.lib.units.perSecond import com.ctre.phoenix6.controls.PositionVoltage as PositionVoltagePhoenix6 class PositionVoltage( - var position: Angle, // Assuming an AngularPosition type exists similar to AngularVelocity - var enableFOC: Boolean = true, - var feedforward: ElectricalPotential = 0.0.volts, - var slot: Int = 0, - var overrideBrakeDurNeutral: Boolean = false, - var limitForwardMotion: Boolean = false, - var limitReverseMotion: Boolean = false, - var velocity: AngularVelocity = 0.0.degrees.perSecond, + private var position: Angle, // Assuming an AngularPosition type exists similar to AngularVelocity + private var enableFOC: Boolean = true, + private var feedforward: ElectricalPotential = 0.0.volts, + private var slot: Int = 0, + private var overrideBrakeDurNeutral: Boolean = false, + private var limitForwardMotion: Boolean = false, + private var limitReverseMotion: Boolean = false, + private var velocity: AngularVelocity = 0.0.degrees.perSecond ) { val positionVoltagePhoenix6 = PositionVoltagePhoenix6(position.inRotations, velocity.inRotationsPerSecond, enableFOC, feedforward.inVolts, slot, overrideBrakeDurNeutral, limitForwardMotion, limitReverseMotion) diff --git a/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt b/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt index 02aa536c..8a9d6e04 100644 --- a/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt +++ b/src/main/kotlin/com/team4099/robot2023/BuildConstants.kt @@ -6,10 +6,10 @@ package com.team4099.robot2023 const val MAVEN_GROUP = "" const val MAVEN_NAME = "Crescendo-2024" const val VERSION = "unspecified" -const val GIT_REVISION = 30 -const val GIT_SHA = "4abb5a7f1e6932895bda561c4716efc84f427d1e" -const val GIT_DATE = "2024-01-19T19:51:08Z" +const val GIT_REVISION = 83 +const val GIT_SHA = "127888ea2c738b8d88ce875b8543d24eb247383f" +const val GIT_DATE = "2024-01-20T19:12:36Z" const val GIT_BRANCH = "shooter" -const val BUILD_DATE = "2024-01-20T15:27:59Z" -const val BUILD_UNIX_TIME = 1705782479283L +const val BUILD_DATE = "2024-01-20T19:59:56Z" +const val BUILD_UNIX_TIME = 1705798796502L const val DIRTY = 1 diff --git a/src/main/kotlin/com/team4099/robot2023/RobotContainer.kt b/src/main/kotlin/com/team4099/robot2023/RobotContainer.kt index c04891d5..b9c55d0d 100644 --- a/src/main/kotlin/com/team4099/robot2023/RobotContainer.kt +++ b/src/main/kotlin/com/team4099/robot2023/RobotContainer.kt @@ -9,9 +9,6 @@ import com.team4099.robot2023.subsystems.drivetrain.drive.Drivetrain import com.team4099.robot2023.subsystems.drivetrain.drive.DrivetrainIO import com.team4099.robot2023.subsystems.drivetrain.drive.DrivetrainIOSim import com.team4099.robot2023.subsystems.drivetrain.gyro.GyroIO -import com.team4099.robot2023.subsystems.intake.Intake -import com.team4099.robot2023.subsystems.intake.IntakeIONEO -import com.team4099.robot2023.subsystems.intake.IntakeIOSim import com.team4099.robot2023.subsystems.limelight.LimelightVision import com.team4099.robot2023.subsystems.limelight.LimelightVisionIO import com.team4099.robot2023.subsystems.superstructure.Request.DrivetrainRequest as DrivetrainRequest @@ -27,7 +24,6 @@ import org.team4099.lib.units.derived.degrees object RobotContainer { private val drivetrain: Drivetrain - private val intake: Intake private val vision: Vision private val limelight: LimelightVision @@ -36,7 +32,6 @@ object RobotContainer { // Real Hardware Implementations // drivetrain = Drivetrain(object: GyroIO {},object: DrivetrainIO {} drivetrain = Drivetrain(object : GyroIO {}, object : DrivetrainIO {}) - intake = Intake(IntakeIONEO) vision = Vision( // object: CameraIO {} @@ -51,7 +46,6 @@ object RobotContainer { } else { // Simulation implementations drivetrain = Drivetrain(object : GyroIO {}, DrivetrainIOSim) - intake = Intake(IntakeIOSim) vision = Vision( CameraIONorthstar("northstar_1"), diff --git a/src/main/kotlin/com/team4099/robot2023/subsystems/flywheel/FlywheelIOTalon.kt b/src/main/kotlin/com/team4099/robot2023/subsystems/flywheel/FlywheelIOTalon.kt index 0fe68ff6..47df57ff 100644 --- a/src/main/kotlin/com/team4099/robot2023/subsystems/flywheel/FlywheelIOTalon.kt +++ b/src/main/kotlin/com/team4099/robot2023/subsystems/flywheel/FlywheelIOTalon.kt @@ -29,7 +29,7 @@ object FlywheelIOTalon : FlywheelIO{ private val flywheelRightSensor = ctreAngularMechanismSensor( flywheelRightTalon, - FlywheelConstants.ROLLER_GEAR_RATIO, + FlywheelConstants.LEFT_GEAR_RATIO, FlywheelConstants.RIGHT_FLYWHEEL_VOLTAGE_COMPENSATION, ) @@ -37,7 +37,7 @@ object FlywheelIOTalon : FlywheelIO{ private val flywheelLeftSensor = ctreAngularMechanismSensor( flywheelLeftTalon, - FlywheelConstants.ROLLER_GEAR_RATIO, + FlywheelConstants.RIGHT_GEAR_RATIO, FlywheelConstants.LEFT_FLYWHEEL_VOLTAGE_COMPENSATION, ) @@ -62,18 +62,18 @@ object FlywheelIOTalon : FlywheelIO{ flywheelLeftTalon.configurator.apply(flywheelLeftConfiguration) flywheelRightConfiguration.Slot0.kP = - flywheelRightSensor.proportionalVelocityGainToRawUnits(FlywheelConstants.SHOOTER_FLYWHEEL_KP) + flywheelRightSensor.proportionalVelocityGainToRawUnits(FlywheelConstants.PID.REAL_KP) flywheelRightConfiguration.Slot0.kI = - flywheelRightSensor.integralVelocityGainToRawUnits(FlywheelConstants.SHOOTER_FLYWHEEL_KI) + flywheelRightSensor.integralVelocityGainToRawUnits(FlywheelConstants.PID.REAL_KI) flywheelRightConfiguration.Slot0.kD = - flywheelRightSensor.derivativeVelocityGainToRawUnits(FlywheelConstants.SHOOTER_FLYWHEEL_KD) + flywheelRightSensor.derivativeVelocityGainToRawUnits(FlywheelConstants.PID.REAL_KD) flywheelLeftConfiguration.Slot0.kP = - flywheelLeftSensor.proportionalVelocityGainToRawUnits(FlywheelConstants.SHOOTER_FLYWHEEL_KP) + flywheelLeftSensor.proportionalVelocityGainToRawUnits(FlywheelConstants.PID.REAL_KP) flywheelRightConfiguration.Slot0.kI = - flywheelLeftSensor.integralVelocityGainToRawUnits(FlywheelConstants.SHOOTER_FLYWHEEL_KI) + flywheelLeftSensor.integralVelocityGainToRawUnits(FlywheelConstants.PID.REAL_KI) flywheelRightConfiguration.Slot0.kD = - flywheelLeftSensor.derivativeVelocityGainToRawUnits(FlywheelConstants.SHOOTER_FLYWHEEL_KD) + flywheelLeftSensor.derivativeVelocityGainToRawUnits(FlywheelConstants.PID.REAL_KD) // flywheelSensor.velocityFeedforwardToRawUnits(FlywheelConstantsConstants.PID.flywheel_KFF) flywheelRightConfiguration.CurrentLimits.SupplyCurrentLimit = @@ -191,13 +191,13 @@ object FlywheelIOTalon : FlywheelIO{ inputs.rightFlywheelAppliedVoltage = rightFlywheelDutyCycle.value.volts inputs.rightFlywheelStatorCurrent = rightFlywheelStatorCurrentSignal.value.amps inputs.rightFlywheelSupplyCurrent = rightFlywheelSupplyCurrentSignal.value.amps - inputs.rightFlywheelTempreature = rightFlywheelTempSignal.value.celsius + inputs.rightFlywheelTemperature = rightFlywheelTempSignal.value.celsius inputs.leftFlywheelVelocity = flywheelLeftSensor.velocity inputs.leftFlywheelAppliedVoltage = leftFlywheelDutyCycle.value.volts inputs.leftFlywheelStatorCurrent = leftFlywheelStatorCurrentSignal.value.amps inputs.leftFlywheelSupplyCurrent = leftFlywheelSupplyCurrentSignal.value.amps - inputs.leftFlywheelTempreature = leftFlywheelTempSignal.value.celsius + inputs.leftFlywheelTemperature = leftFlywheelTempSignal.value.celsius } override fun setLeftFlywheelBrakeMode(brake: Boolean) {