Skip to content

Commit

Permalink
clear a bunch of stuff, for nike
Browse files Browse the repository at this point in the history
  • Loading branch information
Anhysteretic committed Nov 6, 2024
1 parent ae23278 commit 5dfb102
Show file tree
Hide file tree
Showing 6 changed files with 105 additions and 301 deletions.
2 changes: 1 addition & 1 deletion .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024",
"teamNumber": 841
"teamNumber": 9998
}
2 changes: 1 addition & 1 deletion src/main/java/com/team841/calliope/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
public class Robot extends LoggedRobot {
private Command m_autonomousCommand;

private final DigitalInput intakeSensor = new DigitalInput(RC.robot == RC.Robot.CALLIOPE ? 0 : 2);
private final DigitalInput intakeSensor = new DigitalInput(2);

public static RobotContainer m_robotContainer;

Expand Down
51 changes: 12 additions & 39 deletions src/main/java/com/team841/calliope/RobotContainer.java
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
package com.team841.calliope;

import com.ctre.phoenix6.Utils;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule;
import com.ctre.phoenix6.mechanisms.swerve.SwerveRequest;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.team841.calliope.constants.RC;
import com.team841.calliope.constants.Swerve;
import com.team841.calliope.constants.SwerveNike;
import com.team841.calliope.drive.BioDrive;
import com.team841.calliope.drive.Drivetrain;
import com.team841.calliope.superstructure.Shoot;
Expand All @@ -30,12 +28,9 @@
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.*;
import edu.wpi.first.wpilibj2.command.button.CommandGenericHID;
import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;

import static com.team841.calliope.constants.Swerve.DrivetrainConstants;

public class RobotContainer {

public final Drivetrain drivetrain;
Expand Down Expand Up @@ -96,10 +91,7 @@ public static RobotContainer getInstance() {
public RobotContainer() {
switch (RC.robotType) {
default -> {
if (RC.robot == RC.Robot.CALLIOPE)
this.drivetrain = new Drivetrain(Swerve.DrivetrainConstants, Swerve.FrontLeft, Swerve.FrontRight, Swerve.BackLeft, Swerve.BackRight);
else
this.drivetrain = new Drivetrain(SwerveNike.DrivetrainConstants, SwerveNike.FrontLeft, SwerveNike.FrontRight, SwerveNike.BackLeft, SwerveNike.BackRight);
this.drivetrain = new Drivetrain(Swerve.DrivetrainConstants, Swerve.FrontLeft, Swerve.FrontRight, Swerve.BackLeft, Swerve.BackRight);

this.shooterIO = new ShooterIOTalonFX();
this.shooter = new Shooter(this.shooterIO);
Expand All @@ -120,32 +112,16 @@ public RobotContainer() {

registerNamedCommands();

this.sticksXbox = new CommandXboxController[1];
this.sticksPS5 = new CommandPS5Controller[1];
this.sticksXbox[0] = new CommandXboxController(RC.Controllers.soloStick);

if (RC.robot == RC.Robot.NIKE){
this.sticksXbox = new CommandXboxController[1];
this.sticksPS5 = new CommandPS5Controller[1];
this.sticksXbox[0] = new CommandXboxController(RC.Controllers.soloStick);

this.bioDrive = new BioDrive(
this.drivetrain,
() -> -sticksXbox[0].getLeftY() * Swerve.MaxSpeed,
() -> -sticksXbox[0].getLeftX() * Swerve.MaxSpeed,
() -> -sticksXbox[0].getRightX() * Swerve.MaxAngularRate,
() -> sticksXbox[0].a().getAsBoolean());

} else {
this.sticksPS5 = new CommandPS5Controller[1];
this.sticksXbox = new CommandXboxController[1];
this.sticksPS5[0] = new CommandPS5Controller(RC.Controllers.duoStickDrive);
this.sticksXbox[0] = new CommandXboxController(RC.Controllers.duoStickCoDrive);

this.bioDrive = new BioDrive(
this.drivetrain,
() -> -sticksPS5[0].getLeftY() * Swerve.MaxSpeed,
() -> -sticksPS5[0].getLeftX() * Swerve.MaxSpeed,
() -> -sticksPS5[0].getRightX() * Swerve.MaxAngularRate,
() -> sticksPS5[0].L2().getAsBoolean());
}
this.bioDrive = new BioDrive(
this.drivetrain,
() -> -sticksXbox[0].getLeftY() * Swerve.MaxSpeed,
() -> -sticksXbox[0].getLeftX() * Swerve.MaxSpeed,
() -> -sticksXbox[0].getRightX() * Swerve.MaxAngularRate,
() -> sticksXbox[0].a().getAsBoolean());

this.feedback = new Feedback(this.sticksXbox[0]);

Expand All @@ -163,11 +139,8 @@ public RobotContainer() {

this.drivetrain.setDefaultCommand(bioDrive);

if (RC.robot == RC.Robot.NIKE){
configureSoloStick();
} else {
configureDuoStick();
}
configureSoloStick();

}


Expand Down
7 changes: 0 additions & 7 deletions src/main/java/com/team841/calliope/constants/RC.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@ public class RC {

public static final RunType robotType = RunType.COMP;

public static Robot robot = Robot.CALLIOPE;

public static boolean motorsAreWorking = true;

public static class Controllers {
Expand Down Expand Up @@ -52,9 +50,4 @@ public enum RunType{
COMP, // Comp code, real robot code
REPLAY
}

public enum Robot{
CALLIOPE,
NIKE
}
}
181 changes: 91 additions & 90 deletions src/main/java/com/team841/calliope/constants/Swerve.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package com.team841.calliope.constants;

import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.*;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModule.ClosedLoopOutputType;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants;
Expand All @@ -17,56 +17,73 @@ public class Swerve {

// The steer motor uses any SwerveModule.SteerRequestType control request with the
// output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput
private static final Slot0Configs steerGains =
new Slot0Configs().withKP(100).withKI(0).withKD(0.2).withKS(0).withKV(1.5).withKA(0);
public static final Slot0Configs steerGains = new Slot0Configs()
.withKP(100).withKI(0).withKD(0.2)
.withKS(0).withKV(1.5).withKA(0);
// When using closed-loop control, the drive motor uses the control
// output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput
private static final Slot0Configs driveGains =
new Slot0Configs().withKP(3).withKI(0).withKD(0).withKS(0).withKV(0).withKA(0);
public static final Slot0Configs driveGains = new Slot0Configs()
.withKP(3).withKI(0).withKD(0)
.withKS(0).withKV(0).withKA(0);

// The closed-loop output type to use for the steer motors;
// This affects the PID/FF gains for the steer motors
private static final ClosedLoopOutputType steerClosedLoopOutput = ClosedLoopOutputType.Voltage;
public static final ClosedLoopOutputType steerClosedLoopOutput = ClosedLoopOutputType.Voltage;
// The closed-loop output type to use for the drive motors;
// This affects the PID/FF gains for the drive motors
private static final ClosedLoopOutputType driveClosedLoopOutput = ClosedLoopOutputType.Voltage;
public static final ClosedLoopOutputType driveClosedLoopOutput = ClosedLoopOutputType.Voltage;

// The stator current at which the wheels start to slip;
// This needs to be tuned to your individual robot
// private static final double kSlipCurrentA = 300.0;
private static final double kSlipCurrentA = 80.0;
public static final double kSlipCurrentA = 150.0;

// Initial configs for the drive and steer motors and the CANcoder; these cannot be null.
// Some configs will be overwritten; check the `with*InitialConfigs()` API documentation.
public static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration();
public static final TalonFXConfiguration steerInitialConfigs = new TalonFXConfiguration()
.withCurrentLimits(
new CurrentLimitsConfigs()
// Swerve azimuth does not require much torque output, so we can set a relatively low
// stator current limit to help avoid brownouts without impacting performance.
.withStatorCurrentLimit(60)
.withStatorCurrentLimitEnable(true)
);
public static final CANcoderConfiguration cancoderInitialConfigs = new CANcoderConfiguration();
// Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs
public static final Pigeon2Configuration pigeonConfigs = null;

// Theoretical free speed (m/s) at 12v applied output;
// This needs to be tuned to your individual robot
public static final double kSpeedAt12VoltsMps = 5.96;
public static final double kSpeedAt12VoltsMps = 5.21;

// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
// This may need to be tuned to your individual robot
private static final double kCoupleRatio = 3.125;
public static final double kCoupleRatio = 3.5714285714285716;

private static final double kDriveGearRatio = 5.357142857142857;
private static final double kSteerGearRatio = 21.428571428571427;
private static final double kWheelRadiusInches = 2;
public static final double kDriveGearRatio = 6.122448979591837;
public static final double kSteerGearRatio = 21.428571428571427;
public static final double kWheelRadiusInches = 2;

private static final boolean kSteerMotorReversed = true;
private static final boolean kInvertLeftSide = true;
private static final boolean kInvertRightSide = false;
public static final boolean kInvertLeftSide = true;
public static final boolean kInvertRightSide = false;

public static final String kCANbusName = "canivore2";
public static final int kPigeonId = 0;

private static final String kCANbusName = "canivore2";
private static final int kPigeonId = 0;

// These are only used for simulation
private static final double kSteerInertia = 0.00001;
private static final double kDriveInertia = 0.001;
public static final double kSteerInertia = 0.00001;
public static final double kDriveInertia = 0.001;
// Simulated voltage necessary to overcome friction
private static final double kSteerFrictionVoltage = 0.25;
private static final double kDriveFrictionVoltage = 0.25;
public static final double kSteerFrictionVoltage = 0.25;
public static final double kDriveFrictionVoltage = 0.25;

public static final SwerveDrivetrainConstants DrivetrainConstants =
new SwerveDrivetrainConstants().withPigeon2Id(kPigeonId).withCANbusName(kCANbusName);
public static final SwerveDrivetrainConstants DrivetrainConstants = new SwerveDrivetrainConstants()
.withCANbusName(kCANbusName)
.withPigeon2Id(kPigeonId)
.withPigeon2Configs(pigeonConfigs);

public static final SwerveModuleConstantsFactory ConstantCreator =
new SwerveModuleConstantsFactory()
public static final SwerveModuleConstantsFactory ConstantCreator = new SwerveModuleConstantsFactory()
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
.withWheelRadius(kWheelRadiusInches)
Expand All @@ -82,80 +99,64 @@ public class Swerve {
.withDriveFrictionVoltage(kDriveFrictionVoltage)
.withFeedbackSource(SteerFeedbackType.FusedCANcoder)
.withCouplingGearRatio(kCoupleRatio)
.withSteerMotorInverted(kSteerMotorReversed);
.withDriveMotorInitialConfigs(driveInitialConfigs)
.withSteerMotorInitialConfigs(steerInitialConfigs)
.withCANcoderInitialConfigs(cancoderInitialConfigs);


// Front Left
private static final int kFrontLeftDriveMotorId = 3;
private static final int kFrontLeftSteerMotorId = 4;
private static final int kFrontLeftEncoderId = 2;
private static final double kFrontLeftEncoderOffset = -0.421875;
public static final int kFrontLeftDriveMotorId = 3;
public static final int kFrontLeftSteerMotorId = 4;
public static final int kFrontLeftEncoderId = 2;
public static final double kFrontLeftEncoderOffset = -0.107666015625;
public static final boolean kFrontLeftSteerInvert = true;

private static final double kFrontLeftXPosInches = 10.375;
private static final double kFrontLeftYPosInches = 10.375;
public static final double kFrontLeftXPosInches = 10.375;
public static final double kFrontLeftYPosInches = 10.375;

// Front Right
private static final int kFrontRightDriveMotorId = 1;
private static final int kFrontRightSteerMotorId = 2;
private static final int kFrontRightEncoderId = 1;
private static final double kFrontRightEncoderOffset = -0.472412109375;
public static final int kFrontRightDriveMotorId = 1;
public static final int kFrontRightSteerMotorId = 2;
public static final int kFrontRightEncoderId = 1;
public static final double kFrontRightEncoderOffset = -0.296875;
public static final boolean kFrontRightSteerInvert = true;

private static final double kFrontRightXPosInches = 10.375;
private static final double kFrontRightYPosInches = -10.375;
public static final double kFrontRightXPosInches = 10.375;
public static final double kFrontRightYPosInches = -10.375;

// Back Left
private static final int kBackLeftDriveMotorId = 5;
private static final int kBackLeftSteerMotorId = 6;
private static final int kBackLeftEncoderId = 3;
private static final double kBackLeftEncoderOffset = 0.435302734375;
public static final int kBackLeftDriveMotorId = 5;
public static final int kBackLeftSteerMotorId = 6;
public static final int kBackLeftEncoderId = 3;
public static final double kBackLeftEncoderOffset = 0.2412109375;
public static final boolean kBackLeftSteerInvert = true;

private static final double kBackLeftXPosInches = -10.375;
private static final double kBackLeftYPosInches = 10.375;
public static final double kBackLeftXPosInches = -10.375;
public static final double kBackLeftYPosInches = 10.375;

// Back Right
private static final int kBackRightDriveMotorId = 7;
private static final int kBackRightSteerMotorId = 8;
private static final int kBackRightEncoderId = 4;
private static final double kBackRightEncoderOffset = -0.0185546875;

private static final double kBackRightXPosInches = -10.375;
private static final double kBackRightYPosInches = -10.375;

public static final SwerveModuleConstants FrontLeft =
ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId,
kFrontLeftDriveMotorId,
kFrontLeftEncoderId,
kFrontLeftEncoderOffset,
Units.inchesToMeters(kFrontLeftXPosInches),
Units.inchesToMeters(kFrontLeftYPosInches),
kInvertLeftSide);
public static final SwerveModuleConstants FrontRight =
ConstantCreator.createModuleConstants(
kFrontRightSteerMotorId,
kFrontRightDriveMotorId,
kFrontRightEncoderId,
kFrontRightEncoderOffset,
Units.inchesToMeters(kFrontRightXPosInches),
Units.inchesToMeters(kFrontRightYPosInches),
kInvertRightSide);
public static final SwerveModuleConstants BackLeft =
ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId,
kBackLeftDriveMotorId,
kBackLeftEncoderId,
kBackLeftEncoderOffset,
Units.inchesToMeters(kBackLeftXPosInches),
Units.inchesToMeters(kBackLeftYPosInches),
kInvertLeftSide);
public static final SwerveModuleConstants BackRight =
ConstantCreator.createModuleConstants(
kBackRightSteerMotorId,
kBackRightDriveMotorId,
kBackRightEncoderId,
kBackRightEncoderOffset,
Units.inchesToMeters(kBackRightXPosInches),
Units.inchesToMeters(kBackRightYPosInches),
kInvertRightSide);
public static final int kBackRightDriveMotorId = 7;
public static final int kBackRightSteerMotorId = 8;
public static final int kBackRightEncoderId = 4;
public static final double kBackRightEncoderOffset = -0.186279296875;
public static final boolean kBackRightSteerInvert = true;

public static final double kBackRightXPosInches = -10.375;
public static final double kBackRightYPosInches = -10.375;


public static final SwerveModuleConstants FrontLeft = ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset, Units.inchesToMeters(kFrontLeftXPosInches), Units.inchesToMeters(kFrontLeftYPosInches), kInvertLeftSide)
.withSteerMotorInverted(kFrontLeftSteerInvert);
public static final SwerveModuleConstants FrontRight = ConstantCreator.createModuleConstants(
kFrontRightSteerMotorId, kFrontRightDriveMotorId, kFrontRightEncoderId, kFrontRightEncoderOffset, Units.inchesToMeters(kFrontRightXPosInches), Units.inchesToMeters(kFrontRightYPosInches), kInvertRightSide)
.withSteerMotorInverted(kFrontRightSteerInvert);
public static final SwerveModuleConstants BackLeft = ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset, Units.inchesToMeters(kBackLeftXPosInches), Units.inchesToMeters(kBackLeftYPosInches), kInvertLeftSide)
.withSteerMotorInverted(kBackLeftSteerInvert);
public static final SwerveModuleConstants BackRight = ConstantCreator.createModuleConstants(
kBackRightSteerMotorId, kBackRightDriveMotorId, kBackRightEncoderId, kBackRightEncoderOffset, Units.inchesToMeters(kBackRightXPosInches), Units.inchesToMeters(kBackRightYPosInches), kInvertRightSide)
.withSteerMotorInverted(kBackRightSteerInvert);

public static double MaxAngularRate = 4 * Math.PI; // 1.5 * Math.PI; // 3/4 of a rotation per second max angular velocity
public static double MaxSpeed = kSpeedAt12VoltsMps;
Expand Down
Loading

0 comments on commit 5dfb102

Please sign in to comment.