Skip to content

Commit 400068c

Browse files
committed
Functioning drive base!
Going to tag this as the 1.0.0-alpha-1 release modified: src/main/java/frc/robot/Constants.java modified: src/main/java/frc/robot/RobotContainer.java modified: src/main/java/frc/robot/generated/TunerConstants.java modified: src/main/java/frc/robot/subsystems/drive/DriveConstants.java modified: src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java modified: src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java
1 parent de90c22 commit 400068c

6 files changed

Lines changed: 68 additions & 46 deletions

File tree

src/main/java/frc/robot/Constants.java

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,10 @@ public final class Constants {
5454
*/
5555
private static RobotType robotType = RobotType.COMPBOT;
5656

57+
// Define swerve, auto, and vision types being used
5758
private static SwerveType swerveType = SwerveType.PHOENIX6;
5859
private static AutoType autoType = AutoType.PATHPLANNER;
60+
private static VisionType visionType = VisionType.NONE;
5961

6062
public static boolean disableHAL = false;
6163

@@ -126,6 +128,17 @@ public static AutoType getAutoType() {
126128
return autoType;
127129
}
128130

131+
/** Enumerate the supported vision types */
132+
public static enum VisionType {
133+
PHOTON, // PhotonVision (https://docs.photonvision.org/en/latest/)
134+
NONE // No cameras
135+
}
136+
137+
/** Get the current autonomous path planning type */
138+
public static VisionType getVisionType() {
139+
return visionType;
140+
}
141+
129142
/***************************************************************************/
130143
/* The remainder of this file contains physical and/or software constants for the various subsystems of the robot */
131144

src/main/java/frc/robot/RobotContainer.java

Lines changed: 33 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
import frc.robot.Constants.AprilTagConstants;
4040
import frc.robot.Constants.AprilTagConstants.AprilTagLayoutType;
4141
import frc.robot.Constants.AutoConstants;
42+
import frc.robot.Constants.PowerConstants;
4243
import frc.robot.commands.DriveCommands;
4344
import frc.robot.subsystems.accelerometer.Accelerometer;
4445
import frc.robot.subsystems.drive.Drive;
@@ -105,9 +106,14 @@ public RobotContainer() {
105106
m_drivebase = new Drive();
106107
m_flywheel = new Flywheel(new FlywheelIOSim()); // new Flywheel(new FlywheelIOTalonFX());
107108
m_vision =
108-
new Vision(
109-
this::getAprilTagLayoutType,
110-
new VisionIOPhoton(this::getAprilTagLayoutType, "Photon_CAMNAME"));
109+
switch (Constants.getVisionType()) {
110+
case PHOTON ->
111+
new Vision(
112+
this::getAprilTagLayoutType,
113+
new VisionIOPhoton(this::getAprilTagLayoutType, "Photon_CAMNAME"));
114+
case NONE -> new Vision(this::getAprilTagLayoutType);
115+
default -> null;
116+
};
111117
m_accel = new Accelerometer(m_drivebase.getGyro());
112118
break;
113119

@@ -131,7 +137,7 @@ public RobotContainer() {
131137
// ``PowerMonitoring`` takes all the non-drivebase subsystems for which
132138
// you wish to have power monitoring; DO NOT include ``m_drivebase``,
133139
// as that is automatically monitored.
134-
m_power = new PowerMonitoring(m_flywheel);
140+
m_power = null; // new PowerMonitoring(m_flywheel);
135141

136142
// Set up the SmartDashboard Auto Chooser
137143
autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser());
@@ -192,9 +198,9 @@ private void configureBindings() {
192198
m_drivebase.setDefaultCommand(
193199
DriveCommands.fieldRelativeDrive(
194200
m_drivebase,
195-
() -> -driverXbox.getRightY(),
196-
() -> -driverXbox.getRightX(),
197-
() -> -driverXbox.getLeftX()));
201+
() -> -driverXbox.getLeftY(),
202+
() -> -driverXbox.getLeftX(),
203+
() -> driverXbox.getRightX()));
198204

199205
// Example Commands
200206
// Press B button while driving --> ROBOT-CENTRIC
@@ -205,9 +211,9 @@ private void configureBindings() {
205211
() ->
206212
DriveCommands.robotRelativeDrive(
207213
m_drivebase,
208-
() -> -driverXbox.getRightY(),
209-
() -> -driverXbox.getRightX(),
210-
() -> -driverXbox.getLeftX()),
214+
() -> -driverXbox.getLeftY(),
215+
() -> -driverXbox.getLeftX(),
216+
() -> driverXbox.getRightX()),
211217
m_drivebase));
212218

213219
// Press A button -> BRAKE
@@ -327,32 +333,37 @@ public static class Ports {
327333
//
328334
// 0 1
329335
// 2 3
330-
public static final RobotDeviceId FL_DRIVE = new RobotDeviceId(1, "DriveTrain", 1);
331-
public static final RobotDeviceId FL_ROTATION = new RobotDeviceId(2, "DriveTrain", 2);
336+
public static final RobotDeviceId FL_DRIVE = new RobotDeviceId(1, "DriveTrain", 18);
337+
public static final RobotDeviceId FL_ROTATION = new RobotDeviceId(2, "DriveTrain", 19);
332338
public static final RobotDeviceId FL_CANCODER = new RobotDeviceId(3, "DriveTrain", null);
333339

334-
public static final RobotDeviceId FR_DRIVE = new RobotDeviceId(4, "DriveTrain", 3);
335-
public static final RobotDeviceId FR_ROTATION = new RobotDeviceId(5, "DriveTrain", 4);
340+
public static final RobotDeviceId FR_DRIVE = new RobotDeviceId(4, "DriveTrain", 17);
341+
public static final RobotDeviceId FR_ROTATION = new RobotDeviceId(5, "DriveTrain", 16);
336342
public static final RobotDeviceId FR_CANCODER = new RobotDeviceId(6, "DriveTrain", null);
337343

338-
public static final RobotDeviceId BL_DRIVE = new RobotDeviceId(7, "DriveTrain", 5);
339-
public static final RobotDeviceId BL_ROTATION = new RobotDeviceId(8, "DriveTrain", 6);
344+
public static final RobotDeviceId BL_DRIVE = new RobotDeviceId(7, "DriveTrain", 1);
345+
public static final RobotDeviceId BL_ROTATION = new RobotDeviceId(8, "DriveTrain", 0);
340346
public static final RobotDeviceId BL_CANCODER = new RobotDeviceId(9, "DriveTrain", null);
341347

342-
public static final RobotDeviceId BR_DRIVE = new RobotDeviceId(10, "DriveTrain", 7);
343-
public static final RobotDeviceId BR_ROTATION = new RobotDeviceId(11, "DriveTrain", 8);
348+
public static final RobotDeviceId BR_DRIVE = new RobotDeviceId(10, "DriveTrain", 2);
349+
public static final RobotDeviceId BR_ROTATION = new RobotDeviceId(11, "DriveTrain", 3);
344350
public static final RobotDeviceId BR_CANCODER = new RobotDeviceId(12, "DriveTrain", null);
345351

346352
public static final RobotDeviceId PIGEON = new RobotDeviceId(13, "DriveTrain", null);
347353

348-
/* POWER DISTRIBUTION CAN ID */
349-
public static final RobotDeviceId POWER_CAN_DEVICE_ID = new RobotDeviceId(1, null);
354+
/* POWER DISTRIBUTION CAN ID (set by device type in PowerConstants) */
355+
public static final RobotDeviceId POWER_CAN_DEVICE_ID =
356+
switch (PowerConstants.kPowerModule) {
357+
case kRev -> new RobotDeviceId(1, null);
358+
case kCTRE -> new RobotDeviceId(0, null);
359+
default -> null;
360+
};
350361

351362
/* SUBSYSTEM CAN DEVICE IDS */
352363
// This is where mechanism subsystem devices are defined
353364
// Example:
354-
public static final RobotDeviceId FLYWHEEL_LEADER = new RobotDeviceId(3, 9);
355-
public static final RobotDeviceId FLYWHEEL_FOLLOWER = new RobotDeviceId(4, 10);
365+
public static final RobotDeviceId FLYWHEEL_LEADER = new RobotDeviceId(3, 8);
366+
public static final RobotDeviceId FLYWHEEL_FOLLOWER = new RobotDeviceId(4, 9);
356367

357368
/* BEAM BREAK and/or LIMIT SWITCH DIO CHANNELS */
358369
// This is where digital I/O feedback devices are defined

src/main/java/frc/robot/generated/TunerConstants.java

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,6 @@
1212
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstantsFactory;
1313
import edu.wpi.first.math.util.Units;
1414

15-
// import frc.robot.subsystems.CommandSwerveDrivetrain;
16-
1715
// Generated by the Tuner X Swerve Project Generator
1816
// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html
1917
public class TunerConstants {
@@ -187,8 +185,4 @@ public class TunerConstants {
187185
Units.inchesToMeters(kBackRightYPosInches),
188186
kInvertRightSide)
189187
.withSteerMotorInverted(kBackRightSteerInvert);
190-
191-
// public static final CommandSwerveDrivetrain DriveTrain = new
192-
// CommandSwerveDrivetrain(DrivetrainConstants, FrontLeft,
193-
// FrontRight, BackLeft, BackRight);
194188
}

src/main/java/frc/robot/subsystems/drive/DriveConstants.java

Lines changed: 18 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -123,8 +123,8 @@ public class DriveConstants {
123123
kPigeonId = TunerConstants.kPigeonId;
124124
kSteerInertia = TunerConstants.kSteerInertia;
125125
kDriveInertia = TunerConstants.kDriveInertia;
126-
kSteerFrictionVoltage = TunerConstants.kSteerFrictionVoltage;
127-
kDriveFrictionVoltage = TunerConstants.kDriveFrictionVoltage;
126+
kSteerFrictionVoltage = 0.0;
127+
kDriveFrictionVoltage = 0.1;
128128
kSteerCurrentLimit = 40.0; // Example from CTRE documentation
129129
kDriveCurrentLimit = 120.0; // Example from CTRE documentation
130130
kOptimalVoltage = 12.0; // Assumed Ideal
@@ -137,7 +137,8 @@ public class DriveConstants {
137137
kFrontLeftDriveType = "kraken";
138138
kFrontLeftSteerType = "kraken";
139139
kFrontLeftEncoderType = "cancoder";
140-
kFrontLeftEncoderOffset = Units.rotationsToRadians(TunerConstants.kFrontLeftEncoderOffset);
140+
kFrontLeftEncoderOffset =
141+
-Units.rotationsToRadians(TunerConstants.kFrontLeftEncoderOffset) + Math.PI;
141142
kFrontLeftDriveInvert = TunerConstants.kInvertLeftSide;
142143
kFrontLeftSteerInvert = TunerConstants.kFrontLeftSteerInvert;
143144
kFrontLeftEncoderInvert = false;
@@ -153,7 +154,7 @@ public class DriveConstants {
153154
kFrontRightSteerType = "kraken";
154155
kFrontRightEncoderType = "cancoder";
155156
kFrontRightEncoderOffset =
156-
Units.rotationsToRadians(TunerConstants.kFrontRightEncoderOffset);
157+
-Units.rotationsToRadians(TunerConstants.kFrontRightEncoderOffset);
157158
kFrontRightDriveInvert = TunerConstants.kInvertRightSide;
158159
kFrontRightSteerInvert = TunerConstants.kFrontRightSteerInvert;
159160
kFrontRightEncoderInvert = false;
@@ -168,7 +169,8 @@ public class DriveConstants {
168169
kBackLeftDriveType = "kraken";
169170
kBackLeftSteerType = "kraken";
170171
kBackLeftEncoderType = "cancoder";
171-
kBackLeftEncoderOffset = Units.rotationsToRadians(TunerConstants.kBackLeftEncoderOffset);
172+
kBackLeftEncoderOffset =
173+
-Units.rotationsToRadians(TunerConstants.kBackLeftEncoderOffset) + Math.PI;
172174
kBackLeftDriveInvert = TunerConstants.kInvertLeftSide;
173175
kBackLeftSteerInvert = TunerConstants.kBackLeftSteerInvert;
174176
kBackLeftEncoderInvert = false;
@@ -183,21 +185,23 @@ public class DriveConstants {
183185
kBackRightDriveType = "kraken";
184186
kBackRightSteerType = "kraken";
185187
kBackRightEncoderType = "cancoder";
186-
kBackRightEncoderOffset = Units.rotationsToRadians(TunerConstants.kBackRightEncoderOffset);
188+
kBackRightEncoderOffset = -Units.rotationsToRadians(TunerConstants.kBackRightEncoderOffset);
187189
kBackRightDriveInvert = TunerConstants.kInvertRightSide;
188190
kBackRightSteerInvert = TunerConstants.kBackRightSteerInvert;
189191
kBackRightEncoderInvert = false;
190192
kBackRightXPosInches = TunerConstants.kBackRightXPosInches;
191193
kBackRightYPosInches = TunerConstants.kBackRightYPosInches;
192-
kDriveP = TunerConstants.driveGains.kP;
193-
kDriveI = TunerConstants.driveGains.kI;
194-
kDriveD = TunerConstants.driveGains.kD;
195-
kDriveF = TunerConstants.driveGains.kV;
194+
// NOTE: The PIDF values from TunerConstants.java make WPILib/AK implemention go crazy
195+
// These values are from the AK example sketches
196+
kDriveP = 0.05;
197+
kDriveI = 0.0;
198+
kDriveD = 0.0;
199+
kDriveF = 0.13;
196200
kDriveIZ = 0.0;
197-
kSteerP = TunerConstants.steerGains.kP;
198-
kSteerI = TunerConstants.steerGains.kI;
199-
kSteerD = TunerConstants.steerGains.kD;
200-
kSteerF = TunerConstants.steerGains.kV;
201+
kSteerP = 7.0;
202+
kSteerI = 0.0;
203+
kSteerD = 0.0;
204+
kSteerF = 0.0;
201205
kSteerIZ = 0.0;
202206
break;
203207

src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ public class GyroIOPigeon2 implements GyroIO<Pigeon2> {
3535

3636
// Constructor
3737
public GyroIOPigeon2() {
38-
pigeon = new Pigeon2(kBackLeftEncoderId, kBackLeftEncoderCanbus);
38+
pigeon = new Pigeon2(kPigeonId, kCANbusName);
3939
pigeon.getConfigurator().apply(new Pigeon2Configuration());
4040
pigeon.getConfigurator().setYaw(0.0);
4141
yaw = pigeon.getYaw();

src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ public ModuleIOTalonFX(int index) {
7878
turnTalon = new TalonFX(kFrontRightSteerMotorId, kFrontRightSteerCanbus);
7979
cancoder = new CANcoder(kFrontRightEncoderId, kFrontRightEncoderCanbus);
8080
absoluteEncoderOffset = new Rotation2d(kFrontRightEncoderOffset);
81-
isTurnMotorInverted = DriveConstants.kFrontRightSteerInvert;
81+
isTurnMotorInverted = kFrontRightSteerInvert;
8282
break;
8383

8484
case 2:
@@ -87,7 +87,7 @@ public ModuleIOTalonFX(int index) {
8787
turnTalon = new TalonFX(kBackLeftSteerMotorId, kBackLeftSteerCanbus);
8888
cancoder = new CANcoder(kBackLeftEncoderId, kBackLeftEncoderCanbus);
8989
absoluteEncoderOffset = new Rotation2d(kBackLeftEncoderOffset);
90-
isTurnMotorInverted = DriveConstants.kBackLeftSteerInvert;
90+
isTurnMotorInverted = kBackLeftSteerInvert;
9191
break;
9292

9393
case 3:
@@ -96,7 +96,7 @@ public ModuleIOTalonFX(int index) {
9696
turnTalon = new TalonFX(kBackRightSteerMotorId, kBackRightSteerCanbus);
9797
cancoder = new CANcoder(kBackRightEncoderId, kBackRightEncoderCanbus);
9898
absoluteEncoderOffset = new Rotation2d(kBackRightEncoderOffset);
99-
isTurnMotorInverted = DriveConstants.kBackRightSteerInvert;
99+
isTurnMotorInverted = kBackRightSteerInvert;
100100
break;
101101

102102
default:

0 commit comments

Comments
 (0)