Skip to content

Commit

Permalink
updated constants for alphabot and v2 bot
Browse files Browse the repository at this point in the history
  • Loading branch information
Gener1cU5ername committed Jan 25, 2025
1 parent 34cac30 commit cf3c465
Show file tree
Hide file tree
Showing 6 changed files with 60 additions and 20 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.robot.constants;

public class CAN {
public class ALPHABOTCAN {
public static final String rioCanbus = "rio";
public static String driveBaseCanbus = "drivebase";

Expand Down
40 changes: 40 additions & 0 deletions src/main/java/frc/robot/constants/V2CAN.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package frc.robot.constants;

public class V2CAN {
public static final String rioCanbus = "rio";
public static String driveBaseCanbus = "drivebase";

public static final int pigeon = 9;

public static final int frontLeftCanCoder = 10;
public static final int frontRightCanCoder = 11;
public static final int backLeftCanCoder = 12;
public static final int backRightCanCoder = 13;

public static final int frontLeftDriveMotor = 20;
public static final int frontLeftTurnMotor = 21;
public static final int frontRightDriveMotor = 22;
public static final int frontRightTurnMotor = 23;
public static final int backLeftDriveMotor = 24;
public static final int backLeftTurnMotor = 25;
public static final int backRightDriveMotor = 26;
public static final int backRightTurnMotor = 27;

public static final int hopperIntakeMotor1 = 30;
public static final int hopperIntakeMotor2 = 31;

public static final int endEffectorPivotMotor = 32;
public static final int endEffectorOuttakeMotor = 35;
public static final int carriagePivotCanCoder = 36;

public static final int elevatorMotor1 = 33;
public static final int elevatorMotor2 = 34;

public static final int groundRollerMotor = 40;
public static final int groundPivotMotor = 41;
public static final int groundPivotCanCoder = 42;

public static final int cageGrabMotor = 50;
public static final int cageArmMotor = 51;
public static final int cageArmCanCoder = 52;
}
26 changes: 13 additions & 13 deletions src/main/java/frc/robot/generated/TunerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.units.measure.*;
import frc.robot.constants.CAN;
import frc.robot.constants.ALPHABOTCAN;
import frc.robot.subsystems.CommandSwerveDrivetrain;

// Generated by the Tuner X Swerve Project Generator for Software Bot/AlphaBot as of 1/6/2025
Expand Down Expand Up @@ -140,9 +140,9 @@ public class TunerConstants {
.withDriveFrictionVoltage(kDriveFrictionVoltage);

// Front Left
private static final int kFrontLeftDriveMotorId = CAN.frontLeftDriveMotor;
private static final int kFrontLeftSteerMotorId = CAN.frontLeftTurnMotor;
private static final int kFrontLeftEncoderId = CAN.frontLeftCanCoder;
private static final int kFrontLeftDriveMotorId = ALPHABOTCAN.frontLeftDriveMotor;
private static final int kFrontLeftSteerMotorId = ALPHABOTCAN.frontLeftTurnMotor;
private static final int kFrontLeftEncoderId = ALPHABOTCAN.frontLeftCanCoder;
private static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.263916015625);
private static final boolean kFrontLeftSteerMotorInverted = false;
private static final boolean kFrontLeftEncoderInverted = false;
Expand All @@ -151,9 +151,9 @@ public class TunerConstants {
private static final Distance kFrontLeftYPos = Inches.of(13.75);

// Front Right
private static final int kFrontRightDriveMotorId = CAN.frontRightDriveMotor;
private static final int kFrontRightSteerMotorId = CAN.frontRightTurnMotor;
private static final int kFrontRightEncoderId = CAN.frontRightCanCoder;
private static final int kFrontRightDriveMotorId = ALPHABOTCAN.frontRightDriveMotor;
private static final int kFrontRightSteerMotorId = ALPHABOTCAN.frontRightTurnMotor;
private static final int kFrontRightEncoderId = ALPHABOTCAN.frontRightCanCoder;
private static final Angle kFrontRightEncoderOffset = Rotations.of(-0.485595703125);
private static final boolean kFrontRightSteerMotorInverted = false;
private static final boolean kFrontRightEncoderInverted = false;
Expand All @@ -162,9 +162,9 @@ public class TunerConstants {
private static final Distance kFrontRightYPos = Inches.of(-13.75);

// Back Left
private static final int kBackLeftDriveMotorId = CAN.backLeftDriveMotor;
private static final int kBackLeftSteerMotorId = CAN.backLeftTurnMotor;
private static final int kBackLeftEncoderId = CAN.backLeftCanCoder;
private static final int kBackLeftDriveMotorId = ALPHABOTCAN.backLeftDriveMotor;
private static final int kBackLeftSteerMotorId = ALPHABOTCAN.backLeftTurnMotor;
private static final int kBackLeftEncoderId = ALPHABOTCAN.backLeftCanCoder;
private static final Angle kBackLeftEncoderOffset = Rotations.of(0.0556640625);
private static final boolean kBackLeftSteerMotorInverted = false;
private static final boolean kBackLeftEncoderInverted = false;
Expand All @@ -173,9 +173,9 @@ public class TunerConstants {
private static final Distance kBackLeftYPos = Inches.of(13.75);

// Back Right
private static final int kBackRightDriveMotorId = CAN.backRightDriveMotor;
private static final int kBackRightSteerMotorId = CAN.backRightTurnMotor;
private static final int kBackRightEncoderId = CAN.backRightCanCoder;
private static final int kBackRightDriveMotorId = ALPHABOTCAN.backRightDriveMotor;
private static final int kBackRightSteerMotorId = ALPHABOTCAN.backRightTurnMotor;
private static final int kBackRightEncoderId = ALPHABOTCAN.backRightCanCoder;
private static final Angle kBackRightEncoderOffset = Rotations.of(-0.201171875);
private static final boolean kBackRightSteerMotorInverted = false;
private static final boolean kBackRightEncoderInverted = false;
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/AlgaeIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.ALGAE;
import frc.robot.constants.CAN;
import frc.robot.constants.ALPHABOTCAN;
import frc.robot.utils.CtreUtils;

public class AlgaeIntake extends SubsystemBase {

private final TalonFX m_algaeMotor = new TalonFX(CAN.algaeMotor);
private final TalonFX m_algaeMotor = new TalonFX(ALPHABOTCAN.algaeMotor);

/** Creates a new Algae. */
public AlgaeIntake() {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/CoralOuttake.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,14 @@
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.constants.CAN;
import frc.robot.constants.ALPHABOTCAN;
import frc.robot.constants.CORALOUTTAKE;
import frc.robot.utils.CtreUtils;

public class CoralOuttake extends SubsystemBase {
private boolean m_isOuttaking = false;
private LinearSystem<N2, N1, N2> outtakePlant = LinearSystemId.createDCMotorSystem(1, 1);
private final TalonFX outtakeMotor = new TalonFX(CAN.coralOuttakeMotor);
private final TalonFX outtakeMotor = new TalonFX(ALPHABOTCAN.coralOuttakeMotor);
private final DCMotorSim outtakeMotorSim =
new DCMotorSim(outtakePlant, CORALOUTTAKE.gearbox); // TODO implement sim code
private double m_desiredPercentOutput;
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/utils/CtreUtils.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.constants.CAN;
import frc.robot.constants.ALPHABOTCAN;

// TODO: This class is also a mess
public final class CtreUtils {
Expand All @@ -23,7 +23,7 @@ public static void initPhoenixServer() {
new Alert("Starting Phoenix Server at: " + Timer.getFPGATimestamp(), AlertType.kInfo);
alert.set(true);
if (RobotBase.isReal()) {
TalonFX dummy = new TalonFX(0, CAN.driveBaseCanbus);
TalonFX dummy = new TalonFX(0, ALPHABOTCAN.driveBaseCanbus);
Timer.delay(5);
dummy.close();
dummy = null;
Expand Down

0 comments on commit cf3c465

Please sign in to comment.