From 58384c7d6eb084d6d1df2faf40475219664086a5 Mon Sep 17 00:00:00 2001 From: Shikhar Date: Tue, 28 Apr 2026 17:52:23 -0600 Subject: [PATCH] get 2024 working --- src/main/java/frc4388/robot/RobotContainer.java | 8 ++++---- src/main/java/frc4388/robot/RobotMap.java | 8 ++++---- .../java/frc4388/robot/constants/BuildConstants.java | 10 +++++----- src/main/java/frc4388/robot/constants/Constants.java | 2 +- .../java/frc4388/robot/constants/ShooterConstants.java | 4 ++-- src/main/java/frc4388/robot/subsystems/Intake.java | 4 +++- .../robot/subsystems/swerve/SwerveDriveConstants.java | 10 +++++----- 7 files changed, 24 insertions(+), 22 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index fbb663b..f8797ff 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -199,7 +199,7 @@ public class RobotContainer { // Arm down new Trigger(() -> !lt_down() && getDeadbandedDriverController().getXButton()) .onTrue(new InstantCommand(() -> { - m_robotMap.m_robotIntake.PIDIn(); + m_robotMap.m_robotIntake.PIDOut(); m_robotMap.m_robotIntake.spinIntakeMotor(); }, m_robotMap.m_robotIntake)) .onFalse(new InstantCommand(() -> m_robotMap.m_robotIntake.stopArmMotor(), m_robotMap.m_robotIntake)); @@ -215,10 +215,10 @@ public class RobotContainer { // Handoff / spit out new Trigger(() -> !lt_down() && getDeadbandedDriverController().getAButton()) .onTrue(new InstantCommand(() -> { - m_robotMap.m_robotIntake.PIDIn(); - m_robotMap.m_robotIntake.stopIntakeMotors(); + // m_robotMap.m_robotIntake.PIDIn(); + m_robotMap.m_robotIntake.handoff(); }, m_robotMap.m_robotIntake)) - .onFalse(new InstantCommand(() -> m_robotMap.m_robotIntake.stopArmMotor(), m_robotMap.m_robotIntake)); + .onFalse(new InstantCommand(() -> m_robotMap.m_robotIntake.stopIntakeMotors(), m_robotMap.m_robotIntake)); // Shoot new Trigger(() -> !lt_down() && rt_down()) diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 6c26de6..22773a4 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -73,7 +73,7 @@ public class RobotMap { public final Intake m_robotIntake; public final Shooter m_robotShooter; - public final Climber m_robotClimber; + // public final Climber m_robotClimber; public RobotMap(SimConstants.Mode mode) { @@ -87,17 +87,17 @@ public class RobotMap { final TalonFX pivotMotor = new TalonFX(IntakeConstants.PIVOT_MOTOR_ID.id); /* Climber Subsystem */ - final TalonFX climbMotor = new TalonFX(ClimbConstants.CLIMB_MOTOR_ID.id); + // final TalonFX climbMotor = new TalonFX(ClimbConstants.CLIMB_MOTOR_ID.id); m_robotIntake = new Intake(intakeMotor, pivotMotor); m_robotShooter = new Shooter(leftShooter, rightShooter); - m_robotClimber = new Climber(climbMotor); + // m_robotClimber = new Climber(climbMotor); FaultTalonFX.addDevice(leftShooter, "Left Shooter"); FaultTalonFX.addDevice(rightShooter, "Right Shooter"); FaultTalonFX.addDevice(intakeMotor, "Intake Motor"); FaultTalonFX.addDevice(pivotMotor, "Pivot Motor"); - FaultTalonFX.addDevice(climbMotor, "Climb Motor"); + // FaultTalonFX.addDevice(climbMotor, "Climb Motor"); switch (mode) { diff --git a/src/main/java/frc4388/robot/constants/BuildConstants.java b/src/main/java/frc4388/robot/constants/BuildConstants.java index 2fec569..3f73901 100644 --- a/src/main/java/frc4388/robot/constants/BuildConstants.java +++ b/src/main/java/frc4388/robot/constants/BuildConstants.java @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2024AcrossTheRidgebotiverse"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 21; - public static final String GIT_SHA = "f74be4b547fafc94c234cef14666422f4c4dd8e8"; - public static final String GIT_DATE = "2024-10-26 12:45:10 MDT"; + public static final int GIT_REVISION = 22; + public static final String GIT_SHA = "80898f9b8989798e047c7ebbc145dd2aa7d4f12e"; + public static final String GIT_DATE = "2026-04-28 16:32:28 MDT"; public static final String GIT_BRANCH = "2026-postseason-demo"; - public static final String BUILD_DATE = "2026-04-28 14:57:26 MDT"; - public static final long BUILD_UNIX_TIME = 1777409846756L; + public static final String BUILD_DATE = "2026-04-28 17:50:07 MDT"; + public static final long BUILD_UNIX_TIME = 1777420207150L; public static final int DIRTY = 1; private BuildConstants(){} diff --git a/src/main/java/frc4388/robot/constants/Constants.java b/src/main/java/frc4388/robot/constants/Constants.java index c7adfca..b24dacc 100644 --- a/src/main/java/frc4388/robot/constants/Constants.java +++ b/src/main/java/frc4388/robot/constants/Constants.java @@ -32,7 +32,7 @@ import frc4388.utility.structs.LEDPatterns; */ public final class Constants { public static final CANBus RIO_CANBUS = CANBus.roboRIO(); - public static final CANBus CANIVORE_CANBUS = new CANBus("drivetrain"); + // public static final CANBus CANIVORE_CANBUS = new CANBus("drivetrain"); // public static final class LiDARConstants { // public static final int REEF_LIDAR_DIO_CHANNEL = 7; diff --git a/src/main/java/frc4388/robot/constants/ShooterConstants.java b/src/main/java/frc4388/robot/constants/ShooterConstants.java index e6727ea..15cbf9f 100644 --- a/src/main/java/frc4388/robot/constants/ShooterConstants.java +++ b/src/main/java/frc4388/robot/constants/ShooterConstants.java @@ -6,8 +6,8 @@ public class ShooterConstants { // public static final int LEFT_SHOOTER_ID = 15; // final // public static final int RIGHT_SHOOTER_ID = 16; // final - public static final CanDevice LEFT_SHOOTER_ID = new CanDevice("Left Shooter Motor", 15); - public static final CanDevice RIGHT_SHOOTER_ID = new CanDevice("Right Shooter Motor", 16); + public static final CanDevice LEFT_SHOOTER_ID = new CanDevice("Left Shooter Motor", 45); + public static final CanDevice RIGHT_SHOOTER_ID = new CanDevice("Right Shooter Motor", 46); diff --git a/src/main/java/frc4388/robot/subsystems/Intake.java b/src/main/java/frc4388/robot/subsystems/Intake.java index f75f227..ab75bac 100644 --- a/src/main/java/frc4388/robot/subsystems/Intake.java +++ b/src/main/java/frc4388/robot/subsystems/Intake.java @@ -33,7 +33,9 @@ public class Intake extends SubsystemBase { // in init function, set slot 0 gains var slot0Configs = new Slot0Configs(); - slot0Configs.kP = 1.3; // An error of 0.5 rotations results in 12 V output + // slot0Configs.kP = 1.3; // An error of 0.5 rotations results in 12 V output + slot0Configs.kP = 0.5; // An error of 0.5 rotations results in 12 V output + slot0Configs.kI = 0.0; // no output for integrated error slot0Configs.kD = 0.21; // A velocity of 1 rps results in 0.1 V output diff --git a/src/main/java/frc4388/robot/subsystems/swerve/SwerveDriveConstants.java b/src/main/java/frc4388/robot/subsystems/swerve/SwerveDriveConstants.java index fbd84ef..15f558c 100644 --- a/src/main/java/frc4388/robot/subsystems/swerve/SwerveDriveConstants.java +++ b/src/main/java/frc4388/robot/subsystems/swerve/SwerveDriveConstants.java @@ -82,7 +82,7 @@ public final class SwerveDriveConstants { private static final class ModuleSpecificConstants { //2025 //Front Left - private static final Angle FRONT_LEFT_ENCODER_OFFSET = Rotations.of(0); + private static final Angle FRONT_LEFT_ENCODER_OFFSET = Rotations.of(-0.364746-0.25); private static final boolean FRONT_LEFT_DRIVE_MOTOR_INVERTED = false; private static final boolean FRONT_LEFT_STEER_MOTOR_INVERTED = true; private static final boolean FRONT_LEFT_ENCODER_INVERTED = false; @@ -90,7 +90,7 @@ public final class SwerveDriveConstants { private static final Distance FRONT_LEFT_YPOS = Inches.of(HALF_HEIGHT); //Front Right - private static final Angle FRONT_RIGHT_ENCODER_OFFSET = Rotations.of(0); + private static final Angle FRONT_RIGHT_ENCODER_OFFSET = Rotations.of(-0.106446-0.25); private static final boolean FRONT_RIGHT_DRIVE_MOTOR_INVERTED = true; private static final boolean FRONT_RIGHT_STEER_MOTOR_INVERTED = true; private static final boolean FRONT_RIGHT_ENCODER_INVERTED = false; @@ -98,7 +98,7 @@ public final class SwerveDriveConstants { private static final Distance FRONT_RIGHT_YPOS = Inches.of(-HALF_HEIGHT); //Back Left - private static final Angle BACK_LEFT_ENCODER_OFFSET = Rotations.of(0); + private static final Angle BACK_LEFT_ENCODER_OFFSET = Rotations.of(-0.019287); private static final boolean BACK_LEFT_DRIVE_MOTOR_INVERTED = false; private static final boolean BACK_LEFT_STEER_MOTOR_INVERTED = true; private static final boolean BACK_LEFT_ENCODER_INVERTED = false; @@ -106,7 +106,7 @@ public final class SwerveDriveConstants { private static final Distance BACK_LEFT_YPOS = Inches.of(HALF_HEIGHT); //Back Right - private static final Angle BACK_RIGHT_ENCODER_OFFSET = Rotations.of(0); + private static final Angle BACK_RIGHT_ENCODER_OFFSET = Rotations.of(-0.603516-0.25); private static final boolean BACK_RIGHT_DRIVE_MOTOR_INVERTED = false; private static final boolean BACK_RIGHT_STEER_MOTOR_INVERTED = true; private static final boolean BACK_RIGHT_ENCODER_INVERTED = false; @@ -212,7 +212,7 @@ public final class SwerveDriveConstants { } public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants() - .withPigeon2Id(IDs.DRIVE_PIGEON.id).withCANBusName(Constants.CANIVORE_CANBUS.getName()); + .withPigeon2Id(IDs.DRIVE_PIGEON.id).withCANBusName(Constants.RIO_CANBUS.getName()); private static final SwerveModuleConstantsFactory ConstantCreator = new SwerveModuleConstantsFactory() // holy verbosity batman.