diff --git a/src/main/kotlin/frc/team449/RobotLoop.kt b/src/main/kotlin/frc/team449/RobotLoop.kt index adebb0b..5f697ad 100644 --- a/src/main/kotlin/frc/team449/RobotLoop.kt +++ b/src/main/kotlin/frc/team449/RobotLoop.kt @@ -37,7 +37,7 @@ class RobotLoop : TimedRobot(), Logged { @Log.NT private val field = robot.field private var autoCommand: Command? = null - private var routineMap = hashMapOf() + private var routineMap = hashMapOf() private val controllerBinder = ControllerBindings(robot.driveController, robot.mechController, robot) override fun robotInit() { diff --git a/src/main/kotlin/frc/team449/robot2024/Robot.kt b/src/main/kotlin/frc/team449/robot2024/Robot.kt index 294c09c..22fc34f 100644 --- a/src/main/kotlin/frc/team449/robot2024/Robot.kt +++ b/src/main/kotlin/frc/team449/robot2024/Robot.kt @@ -7,7 +7,7 @@ import frc.team449.RobotBase import frc.team449.control.holonomic.SwerveDrive import frc.team449.control.holonomic.SwerveOrthogonalCommand import frc.team449.robot2024.constants.RobotConstants -import frc.team449.robot2024.subsystems.ProtoUndertaker.Companion.createProtoUndertaker +import frc.team449.robot2024.subsystems.Undertaker.Companion.createProtoUndertaker import frc.team449.system.AHRS import frc.team449.system.light.Light import monologue.Annotations.Log diff --git a/src/main/kotlin/frc/team449/robot2024/constants/field/FieldConstants.kt b/src/main/kotlin/frc/team449/robot2024/constants/field/FieldConstants.kt index 08a0b0d..8a47936 100644 --- a/src/main/kotlin/frc/team449/robot2024/constants/field/FieldConstants.kt +++ b/src/main/kotlin/frc/team449/robot2024/constants/field/FieldConstants.kt @@ -1,6 +1,11 @@ package frc.team449.robot2024.constants.field +import edu.wpi.first.math.geometry.Translation2d + object FieldConstants { - val fieldLength = 16.54175 - val fieldWidth = 8.21055 + const val fieldLength = 16.54175 + const val fieldWidth = 8.21055 + + /** Find these constants in meters for the blue alliance */ + val SUBWOOFER_POSE = Translation2d(1.0, 4.0) } diff --git a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ClimberConstants.kt b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ClimberConstants.kt index c73b295..0c30217 100644 --- a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ClimberConstants.kt +++ b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ClimberConstants.kt @@ -16,4 +16,4 @@ object ClimberConstants { const val KP = 1.0 const val KI = 0.0 const val KD = 0.0 -} \ No newline at end of file +} diff --git a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/PivotConstants.kt b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/PivotConstants.kt new file mode 100644 index 0000000..d9438da --- /dev/null +++ b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/PivotConstants.kt @@ -0,0 +1,37 @@ +package frc.team449.robot2024.constants.subsystem + +import edu.wpi.first.math.util.Units +import kotlin.math.PI + +object PivotConstants { + + const val MOTOR_ID = 46 + const val INVERTED = false + const val CURRENT_LIM = 40 + const val GEARING = 1.0 / 75.0 + const val UPR = 2 * PI + const val FOLLOWER_ID = 47 + const val FOLLOWER_INVERTED = true + + const val NUM_MOTORS = 2 + const val MOMENT_OF_INERTIA = 2.0 + + /** Deviations for Kalman filter in units of radians or radians / seconds */ + val MODEL_POS_DEVIATION = Units.degreesToRadians(10.0) + val MODEL_VEL_DEVIATION = Units.degreesToRadians(20.0) + val ENCODER_POS_DEVIATION = Units.degreesToRadians(0.25) + + /** LQR Position and Velocity tolerances */ + val POS_TOLERANCE = Units.degreesToRadians(0.25) + val VEL_TOLERANCE = Units.degreesToRadians(10.0) + val CONTROL_EFFORT_VOLTS = 12.0 + + val MAX_VOLTAGE = 12.0 + + /** Profile Constraints */ + val MAX_VELOCITY = Units.degreesToRadians(100.0) + val MAX_ACCEL = Units.degreesToRadians(75.0) + + val AMP_ANGLE = Units.degreesToRadians(75.0) + val SUBWOOFER_ANGLE = Units.degreesToRadians(30.0) +} diff --git a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ShooterConstants.kt b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ShooterConstants.kt new file mode 100644 index 0000000..ba9b981 --- /dev/null +++ b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ShooterConstants.kt @@ -0,0 +1,64 @@ +package frc.team449.robot2024.constants.subsystem + +import edu.wpi.first.math.InterpolatingMatrixTreeMap +import edu.wpi.first.math.MatBuilder +import edu.wpi.first.math.Nat +import edu.wpi.first.math.numbers.N1 +import edu.wpi.first.math.numbers.N3 + +object ShooterConstants { + const val RIGHT_MOTOR_ID = 41 + const val RIGHT_MOTOR_INVERTED = false + const val LEFT_MOTOR_ID = 42 + const val LEFT_MOTOR_INVERTED = false + const val CURRENT_LIMIT = 40 + const val UPR = 1.0 + + const val SUBWOOFER_LEFT_SPEED = 100.0 + const val SUBWOOFER_RIGHT_SPEED = 125.0 + + val SHOOTING_MAP = InterpolatingMatrixTreeMap() + + const val LEFT_KS = 0.0 + const val RIGHT_KS = 0.0 + + const val AMP_SCORE_VOLTAGE = 4.0 + const val DURING_INTAKE_VOLTAGE = -3.0 + + /** In meters from the ground */ + const val SHOOTER_HEIGHT = 0.25 + + /** These constants are PER SIDE of the shooter */ + const val MOMENT_OF_INERTIA = 2.50 + const val NUM_MOTORS = 1 + const val GEARING = 1.0 / 1.0 + + const val MODEL_VEL_STDDEV = 3.0 + const val ENCODER_VEL_STDDEV = 0.01 + const val LQR_VEL_TOL = 10.0 / 60.0 + const val LQR_MAX_VOLTS = 12.0 + const val MAX_VOLTAGE = 12.0 + + init { + /** + * Fill with values of optimized left/right and pivot angles + * for a given distance to the Speaker + * + * It may be better to mathematically calculate pivot angle, + * this is something to test + * + * Data is entered as following: + * Right shooter speed, left shooter speed, pivot angle + */ + SHOOTING_MAP.put( + 0.0, + MatBuilder.fill( + Nat.N3(), + Nat.N1(), + 0.0, + 0.0, + 0.0 + ) + ) + } +} diff --git a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ProtoIntakeConstants.kt b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/UndertakerConstants.kt similarity index 89% rename from src/main/kotlin/frc/team449/robot2024/constants/subsystem/ProtoIntakeConstants.kt rename to src/main/kotlin/frc/team449/robot2024/constants/subsystem/UndertakerConstants.kt index 8c4716c..135e10a 100644 --- a/src/main/kotlin/frc/team449/robot2024/constants/subsystem/ProtoIntakeConstants.kt +++ b/src/main/kotlin/frc/team449/robot2024/constants/subsystem/UndertakerConstants.kt @@ -1,6 +1,6 @@ package frc.team449.robot2024.constants.subsystem -object ProtoIntakeConstants { +object UndertakerConstants { const val MOTOR_ID = 7 const val FOLLOLWER_ID = 55 const val FOLLOWER_INV = false diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/Climber.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/Climber.kt index 35e7f44..2dc4dee 100644 --- a/src/main/kotlin/frc/team449/robot2024/subsystems/Climber.kt +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/Climber.kt @@ -18,26 +18,26 @@ class Climber( private val controller: PIDController ) : SubsystemBase() { - fun levelClimb() : Command { - return PIDCommand( - controller, - { robot.drive.roll.degrees }, - { 0.0 }, - { value -> - rightMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT + value) - leftMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT - value) - }, - this - ) - } - - fun extend(): Command { - return this.runOnce { - rightMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE) - leftMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE) - } + fun levelClimb(): Command { + return PIDCommand( + controller, + { robot.drive.roll.degrees }, + { 0.0 }, + { value -> + rightMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT + value) + leftMotor.setVoltage(ClimberConstants.DEFAULT_PID_RETRACT - value) + }, + this + ) + } + fun extend(): Command { + return this.runOnce { + rightMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE) + leftMotor.setVoltage(ClimberConstants.EXTEND_VOLTAGE) } + } + fun retract(): Command { return this.runOnce { rightMotor.setVoltage(ClimberConstants.RETRACT_VOLTAGE) @@ -82,7 +82,6 @@ class Climber( currentLimit = ClimberConstants.CURRENT_LIM, ) - val controller = PIDController(ClimberConstants.KP, ClimberConstants.KI, ClimberConstants.KD) return Climber(robot, rightMotor, leftMotor, controller) diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/Pivot.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/Pivot.kt new file mode 100644 index 0000000..484b72b --- /dev/null +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/Pivot.kt @@ -0,0 +1,161 @@ +package frc.team449.robot2024.subsystems + +import edu.wpi.first.math.Nat +import edu.wpi.first.math.VecBuilder +import edu.wpi.first.math.controller.LinearQuadraticRegulator +import edu.wpi.first.math.estimator.KalmanFilter +import edu.wpi.first.math.numbers.N1 +import edu.wpi.first.math.numbers.N2 +import edu.wpi.first.math.system.LinearSystemLoop +import edu.wpi.first.math.system.plant.DCMotor +import edu.wpi.first.math.system.plant.LinearSystemId +import edu.wpi.first.math.trajectory.TrapezoidProfile +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.Robot +import frc.team449.robot2024.constants.MotorConstants +import frc.team449.robot2024.constants.RobotConstants +import frc.team449.robot2024.constants.field.FieldConstants +import frc.team449.robot2024.constants.subsystem.PivotConstants +import frc.team449.robot2024.constants.subsystem.ShooterConstants +import frc.team449.system.encoder.NEOEncoder +import frc.team449.system.motor.WrappedMotor +import frc.team449.system.motor.createSparkMax +import java.util.function.Supplier + +open class Pivot( + private val motor: WrappedMotor, + private val loop: LinearSystemLoop, + private val profile: TrapezoidProfile, + private val robot: Robot +) : SubsystemBase() { + + open val positionSupplier: Supplier = + Supplier { motor.position } + + private var lastProfileReference = TrapezoidProfile.State(motor.position, motor.velocity) + + init { + loop.reset(VecBuilder.fill(motor.position, motor.velocity)) + this.defaultCommand = hold() + } + + fun hold(): Command { + return this.run { + loop.setNextR(lastProfileReference.position, lastProfileReference.velocity) + loop.correct(VecBuilder.fill(positionSupplier.get())) + loop.predict(RobotConstants.LOOP_TIME) + + motor.setVoltage(loop.getU(0)) + } + } + + fun moveAmp(): Command { + return this.run { + moveToAngle(PivotConstants.AMP_ANGLE) + } + } + + fun moveSubwoofer(): Command { + return this.run { + moveToAngle(PivotConstants.SUBWOOFER_ANGLE) + } + } + + fun pivotShootAnywhere(): Command { + return this.run { + val distance = FieldConstants.SUBWOOFER_POSE.getDistance(robot.drive.pose.translation) + val goal = ShooterConstants.SHOOTING_MAP.get(distance).get(2, 0) + + loop.setNextR(goal, 0.0) + loop.correct(VecBuilder.fill(motor.position)) + loop.predict(RobotConstants.LOOP_TIME) + + motor.setVoltage(loop.getU(0)) + } + } + + private fun moveToAngle(goal: Double) { + lastProfileReference = profile.calculate(RobotConstants.LOOP_TIME, lastProfileReference, TrapezoidProfile.State(goal, 0.0)) + + loop.setNextR(lastProfileReference.position, lastProfileReference.velocity) + loop.correct(VecBuilder.fill(motor.position)) + loop.predict(RobotConstants.LOOP_TIME) + + motor.setVoltage(loop.getU(0)) + } + + fun stop(): Command { + return this.runOnce { + motor.stopMotor() + } + } + + override fun initSendable(builder: SendableBuilder) { + builder.publishConstString("1.0", "Motor Voltages") + builder.addDoubleProperty("1.1 Last Voltage", { motor.lastVoltage }, null) + } + + companion object { + fun createShooter(robot: Robot): Pivot { + val motor = createSparkMax( + "Shooter Right Motor", + PivotConstants.MOTOR_ID, + NEOEncoder.creator( + PivotConstants.GEARING, + PivotConstants.UPR + ), + inverted = PivotConstants.INVERTED, + currentLimit = PivotConstants.CURRENT_LIM, + slaveSparks = mapOf(Pair(PivotConstants.FOLLOWER_ID, PivotConstants.FOLLOWER_INVERTED)) + ) + + val plant = LinearSystemId.createSingleJointedArmSystem( + DCMotor( + MotorConstants.NOMINAL_VOLTAGE, + MotorConstants.STALL_TORQUE, + MotorConstants.STALL_CURRENT, + MotorConstants.FREE_CURRENT, + MotorConstants.FREE_SPEED, + PivotConstants.NUM_MOTORS + ), + PivotConstants.MOMENT_OF_INERTIA, + 1 / PivotConstants.GEARING + ) + + val observer = KalmanFilter( + Nat.N2(), + Nat.N1(), + plant, + VecBuilder.fill(PivotConstants.MODEL_POS_DEVIATION, PivotConstants.MODEL_VEL_DEVIATION), + VecBuilder.fill(PivotConstants.ENCODER_POS_DEVIATION), + RobotConstants.LOOP_TIME + ) + + val controller = LinearQuadraticRegulator( + plant, + VecBuilder.fill(PivotConstants.POS_TOLERANCE, PivotConstants.VEL_TOLERANCE), + VecBuilder.fill(PivotConstants.CONTROL_EFFORT_VOLTS), + RobotConstants.LOOP_TIME + ) + + val loop = LinearSystemLoop( + plant, + controller, + observer, + PivotConstants.MAX_VOLTAGE, + RobotConstants.LOOP_TIME + ) + + val profile = TrapezoidProfile( + TrapezoidProfile.Constraints( + PivotConstants.MAX_VELOCITY, + PivotConstants.MAX_ACCEL + ) + ) + + return Pivot(motor, loop, profile, robot) + } + } +} diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/Shooter.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/Shooter.kt new file mode 100644 index 0000000..e6a4fa8 --- /dev/null +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/Shooter.kt @@ -0,0 +1,188 @@ +package frc.team449.robot2024.subsystems + +import edu.wpi.first.math.Nat +import edu.wpi.first.math.VecBuilder +import edu.wpi.first.math.controller.LinearQuadraticRegulator +import edu.wpi.first.math.estimator.KalmanFilter +import edu.wpi.first.math.numbers.N1 +import edu.wpi.first.math.system.LinearSystemLoop +import edu.wpi.first.math.system.plant.DCMotor +import edu.wpi.first.math.system.plant.LinearSystemId +import edu.wpi.first.util.sendable.SendableBuilder +import edu.wpi.first.wpilibj.DriverStation +import edu.wpi.first.wpilibj2.command.Command +import edu.wpi.first.wpilibj2.command.SubsystemBase +import frc.team449.robot2024.Robot +import frc.team449.robot2024.constants.MotorConstants +import frc.team449.robot2024.constants.RobotConstants +import frc.team449.robot2024.constants.field.FieldConstants +import frc.team449.robot2024.constants.subsystem.ShooterConstants +import frc.team449.system.encoder.NEOEncoder +import frc.team449.system.motor.WrappedMotor +import frc.team449.system.motor.createSparkMax +import java.util.function.Supplier + +open class Shooter( + private val rightMotor: WrappedMotor, + private val leftMotor: WrappedMotor, + private val rightLoop: LinearSystemLoop, + private val leftLoop: LinearSystemLoop, + private val robot: Robot +) : SubsystemBase() { + + open val rightVelocity: Supplier = + Supplier { rightMotor.velocity * ShooterConstants.UPR * ShooterConstants.GEARING } + + open val leftVelocity: Supplier = + Supplier { leftMotor.velocity * ShooterConstants.UPR * ShooterConstants.GEARING } + + init { + this.defaultCommand = updateOnly() + } + + fun updateOnly(): Command { + return this.run { + rightLoop.correct(VecBuilder.fill(rightVelocity.get())) + leftLoop.correct(VecBuilder.fill(leftVelocity.get())) + } + } + + fun shootSubwoofer(): Command { + return this.run { + shootPiece( + ShooterConstants.SUBWOOFER_RIGHT_SPEED, + ShooterConstants.SUBWOOFER_LEFT_SPEED + ) + } + } + + fun shootAnywhere(): Command { + return this.run { + val distance = FieldConstants.SUBWOOFER_POSE.getDistance(robot.drive.pose.translation) + + val rightSpeed = ShooterConstants.SHOOTING_MAP.get(distance).get(0, 0) + val leftSpeed = ShooterConstants.SHOOTING_MAP.get(distance).get(1, 0) + + shootPiece(rightSpeed, leftSpeed) + } + } + + fun scoreAmp(): Command { + return this.runOnce { + leftMotor.setVoltage(ShooterConstants.AMP_SCORE_VOLTAGE) + rightMotor.setVoltage(ShooterConstants.AMP_SCORE_VOLTAGE) + } + } + + fun duringIntake(): Command { + return this.runOnce { + rightMotor.setVoltage(ShooterConstants.DURING_INTAKE_VOLTAGE) + leftMotor.setVoltage(ShooterConstants.DURING_INTAKE_VOLTAGE) + } + } + + private fun shootPiece(rightSpeed: Double, leftSpeed: Double) { + if (DriverStation.isDisabled()) { + rightLoop.correct(VecBuilder.fill(rightVelocity.get())) + leftLoop.correct(VecBuilder.fill(leftVelocity.get())) + } else { + rightLoop.setNextR(rightSpeed) + leftLoop.setNextR(leftSpeed) + + rightLoop.correct(VecBuilder.fill(rightVelocity.get())) + leftLoop.correct(VecBuilder.fill(leftVelocity.get())) + + rightLoop.predict(RobotConstants.LOOP_TIME) + leftLoop.predict(RobotConstants.LOOP_TIME) + + rightMotor.setVoltage(rightLoop.getU(0) + ShooterConstants.RIGHT_KS) + leftMotor.setVoltage(leftLoop.getU(0) + ShooterConstants.LEFT_KS) + } + } + + fun stop(): Command { + return this.runOnce { + leftMotor.stopMotor() + rightMotor.stopMotor() + } + } + + override fun initSendable(builder: SendableBuilder) { + builder.publishConstString("1.0", "Motor Voltages") + builder.addDoubleProperty("1.1 Last Right Voltage", { rightMotor.lastVoltage }, null) + builder.addDoubleProperty("1.2 Last Left Voltage", { leftMotor.lastVoltage }, null) + } + + companion object { + fun createShooter(robot: Robot): Shooter { + val rightMotor = createSparkMax( + "Shooter Right Motor", + ShooterConstants.RIGHT_MOTOR_ID, + NEOEncoder.creator( + ShooterConstants.GEARING, + ShooterConstants.UPR + ), + inverted = ShooterConstants.RIGHT_MOTOR_INVERTED, + currentLimit = ShooterConstants.CURRENT_LIMIT, + ) + + val leftMotor = createSparkMax( + "Shooter Right Motor", + ShooterConstants.LEFT_MOTOR_ID, + NEOEncoder.creator( + ShooterConstants.GEARING, + ShooterConstants.UPR + ), + inverted = ShooterConstants.LEFT_MOTOR_INVERTED, + currentLimit = ShooterConstants.CURRENT_LIMIT, + ) + + val plant = LinearSystemId.createFlywheelSystem( + DCMotor( + MotorConstants.NOMINAL_VOLTAGE, + MotorConstants.STALL_TORQUE, + MotorConstants.STALL_CURRENT, + MotorConstants.FREE_CURRENT, + MotorConstants.FREE_SPEED, + ShooterConstants.NUM_MOTORS + ), + ShooterConstants.MOMENT_OF_INERTIA, + 1 / ShooterConstants.GEARING + ) + + val observer = KalmanFilter( + Nat.N1(), + Nat.N1(), + plant, + VecBuilder.fill(ShooterConstants.MODEL_VEL_STDDEV), + VecBuilder.fill(ShooterConstants.ENCODER_VEL_STDDEV), + RobotConstants.LOOP_TIME + ) + + val controller = LinearQuadraticRegulator( + plant, + VecBuilder.fill(ShooterConstants.LQR_VEL_TOL), + VecBuilder.fill(ShooterConstants.LQR_MAX_VOLTS), + RobotConstants.LOOP_TIME + ) + + val rightLoop = LinearSystemLoop( + plant, + controller, + observer, + ShooterConstants.MAX_VOLTAGE, + RobotConstants.LOOP_TIME + ) + + val leftLoop = LinearSystemLoop( + plant, + controller, + observer, + ShooterConstants.MAX_VOLTAGE, + RobotConstants.LOOP_TIME + ) + + return Shooter(rightMotor, leftMotor, rightLoop, leftLoop, robot) + } + } +} diff --git a/src/main/kotlin/frc/team449/robot2024/subsystems/ProtoUndertaker.kt b/src/main/kotlin/frc/team449/robot2024/subsystems/Undertaker.kt similarity index 63% rename from src/main/kotlin/frc/team449/robot2024/subsystems/ProtoUndertaker.kt rename to src/main/kotlin/frc/team449/robot2024/subsystems/Undertaker.kt index 38d5060..a7484da 100644 --- a/src/main/kotlin/frc/team449/robot2024/subsystems/ProtoUndertaker.kt +++ b/src/main/kotlin/frc/team449/robot2024/subsystems/Undertaker.kt @@ -3,24 +3,24 @@ package frc.team449.robot2024.subsystems 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.ProtoIntakeConstants +import frc.team449.robot2024.constants.subsystem.UndertakerConstants import frc.team449.system.encoder.NEOEncoder import frc.team449.system.motor.WrappedMotor import frc.team449.system.motor.createSparkMax -class ProtoUndertaker( +class Undertaker( private val motor: WrappedMotor ) : SubsystemBase() { fun intake(): Command { return this.runOnce { - motor.setVoltage(ProtoIntakeConstants.INTAKE_VOLTAGE) + motor.setVoltage(UndertakerConstants.INTAKE_VOLTAGE) } } fun outtake(): Command { return this.runOnce { - motor.setVoltage(ProtoIntakeConstants.REVERSE_VOLTAGE) + motor.setVoltage(UndertakerConstants.REVERSE_VOLTAGE) } } @@ -36,20 +36,20 @@ class ProtoUndertaker( } companion object { - fun createProtoUndertaker(): ProtoUndertaker { + fun createProtoUndertaker(): Undertaker { val motor = createSparkMax( "ProtoUndertaker Motor", - ProtoIntakeConstants.MOTOR_ID, + UndertakerConstants.MOTOR_ID, NEOEncoder.creator( 1.0, 1.0 ), - inverted = ProtoIntakeConstants.INVERTED, - currentLimit = ProtoIntakeConstants.CURRENT_LIM, - slaveSparks = mapOf(Pair(ProtoIntakeConstants.FOLLOLWER_ID, ProtoIntakeConstants.FOLLOWER_INV)) + inverted = UndertakerConstants.INVERTED, + currentLimit = UndertakerConstants.CURRENT_LIM, + slaveSparks = mapOf(Pair(UndertakerConstants.FOLLOLWER_ID, UndertakerConstants.FOLLOWER_INV)) ) - return ProtoUndertaker(motor) + return Undertaker(motor) } } } diff --git a/vendordeps/PathplannerLib.json b/vendordeps/PathplannerLib.json index 16a48b0..cae1363 100644 --- a/vendordeps/PathplannerLib.json +++ b/vendordeps/PathplannerLib.json @@ -1,7 +1,7 @@ { "fileName": "PathplannerLib.json", "name": "PathplannerLib", - "version": "2024.1.3", + "version": "2024.1.6", "uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786", "frcYear": "2024", "mavenUrls": [ @@ -12,7 +12,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-java", - "version": "2024.1.3" + "version": "2024.1.6" } ], "jniDependencies": [], @@ -20,7 +20,7 @@ { "groupId": "com.pathplanner.lib", "artifactId": "PathplannerLib-cpp", - "version": "2024.1.3", + "version": "2024.1.6", "libName": "PathplannerLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -35,4 +35,4 @@ ] } ] -} +} \ No newline at end of file diff --git a/vendordeps/photonlib-json-1.0.json b/vendordeps/photonlib-json-1.0.json index 40bc7aa..8b19d38 100644 --- a/vendordeps/photonlib-json-1.0.json +++ b/vendordeps/photonlib-json-1.0.json @@ -1,7 +1,7 @@ { "fileName": "photonlib.json", "name": "photonlib", - "version": "v2024.2.0", + "version": "v2024.2.2", "uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004", "frcYear": "2024", "mavenUrls": [ @@ -14,7 +14,7 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-cpp", - "version": "v2024.2.0", + "version": "v2024.2.2", "libName": "photonlib", "headerClassifier": "headers", "sharedLibrary": true, @@ -29,7 +29,7 @@ { "groupId": "org.photonvision", "artifactId": "photontargeting-cpp", - "version": "v2024.2.0", + "version": "v2024.2.2", "libName": "photontargeting", "headerClassifier": "headers", "sharedLibrary": true, @@ -46,12 +46,12 @@ { "groupId": "org.photonvision", "artifactId": "photonlib-java", - "version": "v2024.2.0" + "version": "v2024.2.2" }, { "groupId": "org.photonvision", "artifactId": "photontargeting-java", - "version": "v2024.2.0" + "version": "v2024.2.2" } ] }