Skip to content

Commit

Permalink
refactor: rename Drivetrain, remove usage of var keyword
Browse files Browse the repository at this point in the history
  • Loading branch information
mimizh2418 committed Jan 12, 2024
1 parent 884bb1a commit dc4d13d
Show file tree
Hide file tree
Showing 9 changed files with 53 additions and 64 deletions.
2 changes: 2 additions & 0 deletions src/main/java/org/team1540/robot2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ public enum Mode {
REPLAY
}

public static final double LOOP_PERIOD_SECS = 0.02;

public static class Drivetrain {
public static final String CAN_BUS = "";
public static final double DRIVE_GEAR_RATIO = (50.0 / 14.0) * (17.0 / 27.0) * (45.0 / 15.0);
Expand Down
38 changes: 19 additions & 19 deletions src/main/java/org/team1540/robot2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,11 +23,11 @@
*/
public class RobotContainer {
// Subsystems
public final Drive drive;
public final Drivetrain drivetrain;

// Controller
public final CommandXboxController controller = new CommandXboxController(0);
public final CommandXboxController controllerCopilot = new CommandXboxController(1);
public final CommandXboxController driver = new CommandXboxController(0);
public final CommandXboxController copilot = new CommandXboxController(1);

// Dashboard inputs
public final LoggedDashboardChooser<Command> autoChooser;
Expand All @@ -39,8 +39,8 @@ public RobotContainer() {
switch (Constants.currentMode) {
case REAL:
// Real robot, instantiate hardware IO implementations
drive =
new Drive(
drivetrain =
new Drivetrain(
new GyroIONavx(),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(3, SwerveFactory.SwerveCorner.FRONT_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(4, SwerveFactory.SwerveCorner.FRONT_RIGHT)),
Expand All @@ -57,8 +57,8 @@ public RobotContainer() {

case SIM:
// Sim robot, instantiate physics sim IO implementations
drive =
new Drive(
drivetrain =
new Drivetrain(
new GyroIO() {},
new ModuleIOSim(),
new ModuleIOSim(),
Expand All @@ -68,8 +68,8 @@ public RobotContainer() {

default:
// Replayed robot, disable IO implementations
drive =
new Drive(
drivetrain =
new Drivetrain(
new GyroIO() {
},
new ModuleIO() {
Expand All @@ -91,7 +91,7 @@ public RobotContainer() {
autoChooser.addOption(
"Drive FF Characterization",
new FeedForwardCharacterization(
drive, drive::runCharacterizationVolts, drive::getCharacterizationVelocity));
drivetrain, drivetrain::runCharacterizationVolts, drivetrain::getCharacterizationVelocity));

// Configure the button bindings
configureButtonBindings();
Expand All @@ -104,17 +104,17 @@ public RobotContainer() {
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
drive.setDefaultCommand(
drivetrain.setDefaultCommand(
DriveCommands.joystickDrive(
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> -controller.getRightX()));
controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));
controller.b().onTrue(
drivetrain,
() -> -driver.getLeftY(),
() -> -driver.getLeftX(),
() -> -driver.getRightX()));
driver.x().onTrue(Commands.runOnce(drivetrain::stopWithX, drivetrain));
driver.b().onTrue(
Commands.runOnce(
() -> drive.setPose(new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
drive
() -> drivetrain.setPose(new Pose2d(drivetrain.getPose().getTranslation(), new Rotation2d())),
drivetrain
).ignoringDisable(true)
);
}
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/org/team1540/robot2024/commands/DriveCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import org.team1540.robot2024.subsystems.drive.Drive;
import org.team1540.robot2024.subsystems.drive.Drivetrain;

import java.util.function.DoubleSupplier;

Expand All @@ -21,7 +21,7 @@ private DriveCommands() {
/**
* Field relative drive command using two joysticks (controlling linear and angular velocities).
*/
public static Command joystickDrive(Drive drive, DoubleSupplier xSupplier, DoubleSupplier ySupplier, DoubleSupplier omegaSupplier) {
public static Command joystickDrive(Drivetrain drivetrain, DoubleSupplier xSupplier, DoubleSupplier ySupplier, DoubleSupplier omegaSupplier) {
return Commands.run(() -> {
// Apply deadband
double linearMagnitude = MathUtil.applyDeadband(Math.hypot(xSupplier.getAsDouble(), ySupplier.getAsDouble()), DEADBAND);
Expand All @@ -36,14 +36,14 @@ public static Command joystickDrive(Drive drive, DoubleSupplier xSupplier, Doubl
Translation2d linearVelocity = new Pose2d(new Translation2d(), linearDirection).transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())).getTranslation();

// Convert to field relative speeds & send command
drive.runVelocity(
drivetrain.runVelocity(
ChassisSpeeds.fromFieldRelativeSpeeds(
linearVelocity.getX() * drive.getMaxLinearSpeedMetersPerSec(),
linearVelocity.getY() * drive.getMaxLinearSpeedMetersPerSec(),
omega * drive.getMaxAngularSpeedRadPerSec(),
drive.getRotation()
linearVelocity.getX() * drivetrain.getMaxLinearSpeedMetersPerSec(),
linearVelocity.getY() * drivetrain.getMaxLinearSpeedMetersPerSec(),
omega * drivetrain.getMaxAngularSpeedRadPerSec(),
drivetrain.getRotation()
)
);
}, drive);
}, drivetrain);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -20,19 +20,17 @@
import org.littletonrobotics.junction.Logger;
import org.team1540.robot2024.Constants;

public class Drive extends SubsystemBase {


public class Drivetrain extends SubsystemBase {
private final GyroIO gyroIO;
private final GyroIOInputsAutoLogged gyroInputs = new GyroIOInputsAutoLogged();
private final Module[] modules = new Module[4]; // FL, FR, BL, BR

private SwerveDriveKinematics kinematics = new SwerveDriveKinematics(getModuleTranslations());
private final SwerveDriveKinematics kinematics = new SwerveDriveKinematics(getModuleTranslations());
private Pose2d pose = new Pose2d();
private Rotation2d lastGyroRotation = new Rotation2d();
private boolean forceModuleAngleChange = false;

public Drive(
public Drivetrain(
GyroIO gyroIO,
ModuleIO flModuleIO,
ModuleIO frModuleIO,
Expand All @@ -55,26 +53,22 @@ public Drive(
this);
Pathfinding.setPathfinder(new LocalADStarAK());
PathPlannerLogging.setLogActivePathCallback(
(activePath) -> {
Logger.recordOutput(
"Odometry/Trajectory", activePath.toArray(new Pose2d[activePath.size()]));
});
(activePath) -> Logger.recordOutput(
"Odometry/Trajectory", activePath.toArray(new Pose2d[activePath.size()])));
PathPlannerLogging.setLogTargetPoseCallback(
(targetPose) -> {
Logger.recordOutput("Odometry/TrajectorySetpoint", targetPose);
});
(targetPose) -> Logger.recordOutput("Odometry/TrajectorySetpoint", targetPose));
}

public void periodic() {
gyroIO.updateInputs(gyroInputs);
Logger.processInputs("Drive/Gyro", gyroInputs);
for (var module : modules) {
Logger.processInputs("Drivetrain/Gyro", gyroInputs);
for (Module module : modules) {
module.periodic();
}

// Stop moving when disabled
if (DriverStation.isDisabled()) {
for (var module : modules) {
for (Module module : modules) {
module.stop();
}
}
Expand All @@ -92,7 +86,7 @@ public void periodic() {
// The twist represents the motion of the robot since the last
// loop cycle in x, y, and theta based only on the modules,
// without the gyro. The gyro is always disconnected in simulation.
var twist = kinematics.toTwist2d(wheelDeltas);
Twist2d twist = kinematics.toTwist2d(wheelDeltas);
if (gyroInputs.connected) {
// If the gyro is connected, replace the theta component of the twist
// with the change in angle since the last loop cycle.
Expand Down Expand Up @@ -163,14 +157,14 @@ public void runCharacterizationVolts(double volts) {
*/
public double getCharacterizationVelocity() {
double driveVelocityAverage = 0.0;
for (var module : modules) {
for (Module module : modules) {
driveVelocityAverage += module.getCharacterizationVelocity();
}
return driveVelocityAverage / 4.0;
}

/**
* Returns the module states (turn angles and drive velocities) for all of the modules.
* Returns the module states (turn angles and drive velocities) for all the modules.
*/
@AutoLogOutput(key = "SwerveStates/Measured")
private SwerveModuleState[] getModuleStates() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@ public GyroIONavx(){
lastAngle = navx.getRotation2d();
}


@Override
public void updateInputs(GyroIOInputs inputs) {
double lastTime = inputs.time;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
import org.littletonrobotics.junction.Logger;

public class Module {

private final ModuleIO io;
private final ModuleIOInputsAutoLogged inputs = new ModuleIOInputsAutoLogged();
private final int index;
Expand Down Expand Up @@ -97,7 +96,7 @@ public SwerveModuleState runSetpoint(SwerveModuleState state) {
public SwerveModuleState runSetpoint(SwerveModuleState state, boolean forceTurn) {
// Optimize state based on current angle
// Controllers run in "periodic" when the setpoint is not null
var optimizedState = SwerveModuleState.optimize(state, getAngle());
SwerveModuleState optimizedState = SwerveModuleState.optimize(state, getAngle());

// Update setpoints, controllers run in "periodic"
angleSetpoint = ((Math.abs(optimizedState.speedMetersPerSecond) <= (Constants.Drivetrain.MAX_LINEAR_SPEED * 0.01)) && !forceTurn) ? angleSetpoint : optimizedState.angle; //Prevent rotating module if speed is less then 1%. Prevents Jittering.
Expand Down Expand Up @@ -174,7 +173,7 @@ public SwerveModulePosition getPosition() {
* Returns the module position delta since the last call to this method.
*/
public SwerveModulePosition getPositionDelta() {
var delta = new SwerveModulePosition(getPositionMeters() - lastPositionMeters, getAngle());
SwerveModulePosition delta = new SwerveModulePosition(getPositionMeters() - lastPositionMeters, getAngle());
lastPositionMeters = getPositionMeters();
return delta;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
import org.team1540.robot2024.Constants;

/**
* Physics sim implementation of module IO.
Expand All @@ -13,7 +14,6 @@
* approximation for the behavior of the module.
*/
public class ModuleIOSim implements ModuleIO {
private static final double LOOP_PERIOD_SECS = 0.02;
private final Rotation2d turnAbsoluteInitPosition = new Rotation2d(Math.random() * 2.0 * Math.PI);
private final DCMotorSim driveSim = new DCMotorSim(DCMotor.getFalcon500Foc(1), 6.15, 0.025);
private final DCMotorSim turnSim = new DCMotorSim(DCMotor.getFalcon500Foc(1), 150.0 / 7.0, 0.004);
Expand All @@ -22,8 +22,8 @@ public class ModuleIOSim implements ModuleIO {

@Override
public void updateInputs(ModuleIOInputs inputs) {
driveSim.update(LOOP_PERIOD_SECS);
turnSim.update(LOOP_PERIOD_SECS);
driveSim.update(Constants.LOOP_PERIOD_SECS);
turnSim.update(Constants.LOOP_PERIOD_SECS);

inputs.drivePositionRad = driveSim.getAngularPositionRad();
inputs.driveVelocityRadPerSec = driveSim.getAngularVelocityRadPerSec();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,6 @@ public class ModuleIOTalonFX implements ModuleIO {
private final StatusSignal<Double> turnAppliedVolts;
private final StatusSignal<Double> turnCurrent;

// Gear ratios for SDS MK4i L2, adjust as necessary


private final Rotation2d absoluteEncoderOffset;

public ModuleIOTalonFX(SwerveFactory.SwerveModuleHW hw) {
Expand All @@ -53,11 +50,9 @@ public ModuleIOTalonFX(SwerveFactory.SwerveModuleHW hw) {
cancoder = hw.cancoder;
absoluteEncoderOffset = hw.cancoderOffset;


setDriveBrakeMode(true);
setTurnBrakeMode(true);


drivePosition = driveTalon.getPosition();
driveVelocity = driveTalon.getVelocity();
driveAppliedVolts = driveTalon.getMotorVoltage();
Expand Down Expand Up @@ -103,15 +98,15 @@ public void setTurnVoltage(double volts) {

@Override
public void setDriveBrakeMode(boolean enable) {
var config = new MotorOutputConfigs();
MotorOutputConfigs config = new MotorOutputConfigs();
config.Inverted = InvertedValue.CounterClockwise_Positive;
config.NeutralMode = enable ? NeutralModeValue.Brake : NeutralModeValue.Coast;
driveTalon.getConfigurator().apply(config);
}

@Override
public void setTurnBrakeMode(boolean enable) {
var config = new MotorOutputConfigs();
MotorOutputConfigs config = new MotorOutputConfigs();
config.Inverted = Constants.Drivetrain.IS_TURN_MOTOR_INVERTED ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive;
config.NeutralMode = enable ? NeutralModeValue.Brake : NeutralModeValue.Coast;
turnTalon.getConfigurator().apply(config);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ private SwerveModuleHW(int id, SwerveCorner corner, String canbus) {
}
TalonFXConfiguration driveConfig = new TalonFXConfiguration();
TalonFXConfiguration turnConfig = new TalonFXConfiguration();
CANcoderConfiguration canCoderconfig = new CANcoderConfiguration();
CANcoderConfiguration canCoderConfig = new CANcoderConfiguration();

driveConfig.CurrentLimits.SupplyCurrentLimit = 40.0;
driveConfig.CurrentLimits.SupplyCurrentThreshold = 60.0;
Expand All @@ -65,9 +65,9 @@ private SwerveModuleHW(int id, SwerveCorner corner, String canbus) {
turnConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
turnConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;

canCoderconfig.MagnetSensor.MagnetOffset = moduleOffsetsRots[id-1];
canCoderconfig.MagnetSensor.SensorDirection = SensorDirectionValue.CounterClockwise_Positive;
canCoderconfig.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Unsigned_0To1;
canCoderConfig.MagnetSensor.MagnetOffset = moduleOffsetsRots[id-1];
canCoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.CounterClockwise_Positive;
canCoderConfig.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Unsigned_0To1;

this.driveMotor = new TalonFX(30 + id, canbus);
this.driveMotor.getConfigurator().apply(driveConfig);
Expand All @@ -79,7 +79,7 @@ private SwerveModuleHW(int id, SwerveCorner corner, String canbus) {
this.cancoder = new CANcoder(10 + id, canbus);


this.cancoder.getConfigurator().apply(canCoderconfig);
this.cancoder.getConfigurator().apply(canCoderConfig);

this.cancoderOffset = Rotation2d.fromDegrees(corner.offset);

Expand Down

0 comments on commit dc4d13d

Please sign in to comment.