Skip to content

Commit

Permalink
module offsets + uninvert steers + moved motors to canbus 2
Browse files Browse the repository at this point in the history
  • Loading branch information
davidchen20 committed Jan 28, 2024
1 parent cca1811 commit a239249
Show file tree
Hide file tree
Showing 8 changed files with 48 additions and 43 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.1.1"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
id "com.peterabeles.gversion" version "1.10"
id "com.diffplug.spotless" version "6.12.0"
}
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "2024RobotCode";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 4;
public static final String GIT_SHA = "6238ea9fb85d7f0c41bd5dec8fe17cb125498b6d";
public static final String GIT_DATE = "2024-01-09 16:05:09 EST";
public static final String GIT_BRANCH = "main";
public static final String BUILD_DATE = "2024-01-12 17:38:42 EST";
public static final long BUILD_UNIX_TIME = 1705099122187L;
public static final int GIT_REVISION = 5;
public static final String GIT_SHA = "cca181101b68569d0f64c2038b7c5ffb0ceb66fb";
public static final String GIT_DATE = "2024-01-12 17:44:29 EST";
public static final String GIT_BRANCH = "swerve";
public static final String BUILD_DATE = "2024-01-27 16:46:30 EST";
public static final long BUILD_UNIX_TIME = 1706391990425L;
public static final int DIRTY = 1;

private BuildConstants() {}
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,11 @@
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static final Mode currentMode = Mode.SIM;
public static final Mode currentMode = Mode.REAL;
public static final boolean tuningMode = true;

public static final String CANBUS = "CAN Bus 2";

public static enum Mode {
/** Running on a real robot. */
REAL,
Expand Down
23 changes: 12 additions & 11 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
import frc.robot.subsystems.drive.GyroIOPigeon2;
import frc.robot.subsystems.drive.ModuleIO;
import frc.robot.subsystems.drive.ModuleIOSim;
import frc.robot.subsystems.drive.ModuleIOSparkMax;
import frc.robot.subsystems.drive.ModuleIOTalonFX;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

/**
Expand All @@ -52,19 +52,20 @@ public RobotContainer() {
switch (Constants.currentMode) {
case REAL:
// Real robot, instantiate hardware IO implementations
// drive =
// new Drive(
// new GyroIOPigeon2(),
// new ModuleIOSparkMax(0),
// new ModuleIOSparkMax(1),
// new ModuleIOSparkMax(2),
// new ModuleIOSparkMax(3));
drive =
new Drive(
new GyroIOPigeon2(),
new ModuleIOSparkMax(0),
new ModuleIOSparkMax(1),
new ModuleIOSparkMax(2),
new ModuleIOSparkMax(3));
// drive = new Drive(
// new GyroIOPigeon2(),
// new ModuleIOTalonFX(0),
// new ModuleIOTalonFX(1),
// new ModuleIOTalonFX(2),
// new ModuleIOTalonFX(3));
new ModuleIOTalonFX(0),
new ModuleIOTalonFX(1),
new ModuleIOTalonFX(2),
new ModuleIOTalonFX(3));
// flywheel = new Flywheel(new FlywheelIOTalonFX());
break;

Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,11 @@
import com.ctre.phoenix6.hardware.Pigeon2;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import frc.robot.Constants;

/** IO implementation for Pigeon2 */
public class GyroIOPigeon2 implements GyroIO {
private final Pigeon2 pigeon = new Pigeon2(0);
private final Pigeon2 pigeon = new Pigeon2(0, Constants.CANBUS);
private final StatusSignal<Double> yaw = pigeon.getYaw();
private final StatusSignal<Double> yawVelocity = pigeon.getAngularVelocityZWorld();

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/drive/Module.java
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ public Module(ModuleIO io, int index) {
}

turnFeedback.enableContinuousInput(-Math.PI, Math.PI);
setBrakeMode(true);
setBrakeMode(false);
}

public void periodic() {
Expand Down
35 changes: 18 additions & 17 deletions src/main/java/frc/robot/subsystems/drive/ModuleIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import frc.robot.Constants;

/**
* Module IO implementation for Talon FX drive motor controller, Talon FX turn motor controller, and
Expand Down Expand Up @@ -58,34 +59,34 @@ public class ModuleIOTalonFX implements ModuleIO {
private final double DRIVE_GEAR_RATIO = 6.12;
private final double TURN_GEAR_RATIO = 150.0 / 7.0;

private final boolean isTurnMotorInverted = true;
private final boolean isTurnMotorInverted = false;
private final Rotation2d absoluteEncoderOffset;

public ModuleIOTalonFX(int index) {
switch (index) {
case 0:
driveTalon = new TalonFX(0);
turnTalon = new TalonFX(4);
cancoder = new CANcoder(0);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
driveTalon = new TalonFX(0, Constants.CANBUS);
turnTalon = new TalonFX(4, Constants.CANBUS);
cancoder = new CANcoder(0, Constants.CANBUS);
absoluteEncoderOffset = new Rotation2d(-2.14); // MUST BE CALIBRATED
break;
case 1:
driveTalon = new TalonFX(1);
turnTalon = new TalonFX(5);
cancoder = new CANcoder(1);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
driveTalon = new TalonFX(1, Constants.CANBUS);
turnTalon = new TalonFX(5, Constants.CANBUS);
cancoder = new CANcoder(1, Constants.CANBUS);
absoluteEncoderOffset = new Rotation2d(-1.82); // MUST BE CALIBRATED
break;
case 2:
driveTalon = new TalonFX(2);
turnTalon = new TalonFX(6);
cancoder = new CANcoder(2);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
driveTalon = new TalonFX(2, Constants.CANBUS);
turnTalon = new TalonFX(6, Constants.CANBUS);
cancoder = new CANcoder(2, Constants.CANBUS);
absoluteEncoderOffset = new Rotation2d(1.74); // MUST BE CALIBRATED
break;
case 3:
driveTalon = new TalonFX(3);
turnTalon = new TalonFX(7);
cancoder = new CANcoder(3);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
driveTalon = new TalonFX(3, Constants.CANBUS);
turnTalon = new TalonFX(7, Constants.CANBUS);
cancoder = new CANcoder(3, Constants.CANBUS);
absoluteEncoderOffset = new Rotation2d(0.98); // MUST BE CALIBRATED
break;
default:
throw new RuntimeException("Invalid module index");
Expand Down
10 changes: 5 additions & 5 deletions vendordeps/AdvantageKit.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "AdvantageKit.json",
"name": "AdvantageKit",
"version": "3.0.0",
"version": "3.0.2",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
"frcYear": "2024",
"mavenUrls": [],
Expand All @@ -10,24 +10,24 @@
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "wpilib-shim",
"version": "3.0.0"
"version": "3.0.2"
},
{
"groupId": "org.littletonrobotics.akit.junction",
"artifactId": "junction-core",
"version": "3.0.0"
"version": "3.0.2"
},
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-api",
"version": "3.0.0"
"version": "3.0.2"
}
],
"jniDependencies": [
{
"groupId": "org.littletonrobotics.akit.conduit",
"artifactId": "conduit-wpilibio",
"version": "3.0.0",
"version": "3.0.2",
"skipInvalidPlatforms": false,
"isJar": false,
"validPlatforms": [
Expand Down

0 comments on commit a239249

Please sign in to comment.