Skip to content

Commit

Permalink
Swerve actually works this time (#2)
Browse files Browse the repository at this point in the history
* fix: module offsets

* refactor: rename Drivetrain, remove usage of var keyword

* feat: put drive command into SwerveDriveCommand

* chore: remove debug print

* fix: swerve motor current is no longer logged as an array

* fix: use gear ratio from constants in sim

* refactor: less verbose constants
  • Loading branch information
mimizh2418 authored Jan 16, 2024
1 parent 2e7caed commit 7d29459
Show file tree
Hide file tree
Showing 12 changed files with 148 additions and 153 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
5 changes: 1 addition & 4 deletions src/main/java/org/team1540/robot2024/Robot.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
package org.team1540.robot2024;

import com.pathplanner.lib.commands.PathPlannerAuto;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
Expand Down Expand Up @@ -39,7 +37,7 @@ public void robotInit() {
Logger.recordMetadata("GitDirty", "All changes committed");
break;
case 1:
Logger.recordMetadata("GitDirty", "Uncomitted changes");
Logger.recordMetadata("GitDirty", "Uncommitted changes");
break;
default:
Logger.recordMetadata("GitDirty", "Unknown");
Expand Down Expand Up @@ -113,7 +111,6 @@ public void disabledPeriodic() {
@Override
public void autonomousInit() {
autonomousCommand = robotContainer.getAutonomousCommand();
robotContainer.drive.setPose(PathPlannerAuto.getStaringPoseFromAutoFile("TestAuto"));
// schedule the autonomous command (example)
if (autonomousCommand != null) {
autonomousCommand.schedule();
Expand Down
55 changes: 21 additions & 34 deletions src/main/java/org/team1540/robot2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import org.team1540.robot2024.commands.DriveCommands;
import org.team1540.robot2024.commands.FeedForwardCharacterization;
import org.team1540.robot2024.commands.SwerveDriveCommand;
import org.team1540.robot2024.subsystems.drive.*;
import org.team1540.robot2024.util.swerve.SwerveFactory;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
Expand All @@ -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,28 +39,20 @@ 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(1, SwerveFactory.SwerveCorner.FRONT_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(7, SwerveFactory.SwerveCorner.FRONT_RIGHT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(4, SwerveFactory.SwerveCorner.BACK_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(3, SwerveFactory.SwerveCorner.BACK_RIGHT)));
// drive = new Drive(
// new GyroIOPigeon2(),
// new ModuleIOTalonFX(0),
// new ModuleIOTalonFX(1),
// new ModuleIOTalonFX(2),
// new ModuleIOTalonFX(3));
// flywheel = new Flywheel(new FlywheelIOTalonFX());
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(3, SwerveFactory.SwerveCorner.FRONT_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(4, SwerveFactory.SwerveCorner.FRONT_RIGHT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(7, SwerveFactory.SwerveCorner.BACK_LEFT)),
new ModuleIOTalonFX(SwerveFactory.getModuleMotors(1, SwerveFactory.SwerveCorner.BACK_RIGHT)));
break;

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

default:
// Replayed robot, disable IO implementations
drive =
new Drive(
drivetrain =
new Drivetrain(
new GyroIO() {
},
new ModuleIO() {
Expand All @@ -92,7 +84,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 @@ -105,17 +97,12 @@ public RobotContainer() {
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
drive.setDefaultCommand(
DriveCommands.joystickDrive(
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> -controller.getRightX()));
controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));
controller.b().onTrue(
drivetrain.setDefaultCommand(new SwerveDriveCommand(drivetrain, driver));
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
49 changes: 0 additions & 49 deletions src/main/java/org/team1540/robot2024/commands/DriveCommands.java

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
package org.team1540.robot2024.commands;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import org.team1540.robot2024.subsystems.drive.Drivetrain;

public class SwerveDriveCommand extends Command {
private final Drivetrain drivetrain;
private final CommandXboxController controller;

private final SlewRateLimiter xLimiter = new SlewRateLimiter(2);
private final SlewRateLimiter yLimiter = new SlewRateLimiter(2);
private final SlewRateLimiter rotLimiter = new SlewRateLimiter(3);

public SwerveDriveCommand(Drivetrain drivetrain, CommandXboxController controller) {
this.drivetrain = drivetrain;
this.controller = controller;
addRequirements(drivetrain);
}

@Override
public void initialize() {
xLimiter.reset(0);
yLimiter.reset(0);
rotLimiter.reset(0);
}

@Override
public void execute() {
double xPercent = xLimiter.calculate(-controller.getLeftY());
double yPercent = yLimiter.calculate(-controller.getLeftX());
double rotPercent = rotLimiter.calculate(-controller.getRightX());

// Apply deadband
double linearMagnitude = MathUtil.applyDeadband(Math.hypot(xPercent, yPercent), 0.1);
Rotation2d linearDirection = new Rotation2d(xPercent, yPercent);
double omega = MathUtil.applyDeadband(rotPercent, 0.1);

// Calculate new linear velocity
Translation2d linearVelocity =
new Pose2d(new Translation2d(), linearDirection)
.transformBy(new Transform2d(linearMagnitude, 0.0, new Rotation2d())).getTranslation();

// Convert to field relative speeds & send command
drivetrain.runVelocity(
ChassisSpeeds.fromFieldRelativeSpeeds(
linearVelocity.getX() * drivetrain.getMaxLinearSpeedMetersPerSec(),
linearVelocity.getY() * drivetrain.getMaxLinearSpeedMetersPerSec(),
omega * drivetrain.getMaxAngularSpeedRadPerSec(),
drivetrain.getRotation()
)
);
}

@Override
public void end(boolean interrupted) {
drivetrain.stop();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,20 @@
import org.team1540.robot2024.util.LocalADStarAK;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import org.team1540.robot2024.Constants;

public class Drive extends SubsystemBase {

import static org.team1540.robot2024.Constants.Drivetrain.*;

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 @@ -50,31 +49,27 @@ public Drive(
this::setPose,
() -> kinematics.toChassisSpeeds(getModuleStates()),
this::runVelocity,
new HolonomicPathFollowerConfig(Constants.Drivetrain.MAX_LINEAR_SPEED, Constants.Drivetrain.DRIVE_BASE_RADIUS, new ReplanningConfig()),
new HolonomicPathFollowerConfig(MAX_LINEAR_SPEED, DRIVE_BASE_RADIUS, new ReplanningConfig()),
() -> DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == DriverStation.Alliance.Red,
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 +87,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 All @@ -114,7 +109,7 @@ public void runVelocity(ChassisSpeeds speeds) {
// Calculate module setpoints
ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, 0.02);
SwerveModuleState[] setpointStates = kinematics.toSwerveModuleStates(discreteSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(setpointStates, Constants.Drivetrain.MAX_LINEAR_SPEED);
SwerveDriveKinematics.desaturateWheelSpeeds(setpointStates, MAX_LINEAR_SPEED);

// Send setpoints to modules
SwerveModuleState[] optimizedSetpointStates = new SwerveModuleState[4];
Expand Down Expand Up @@ -163,14 +158,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 Expand Up @@ -207,25 +202,25 @@ public void setPose(Pose2d pose) {
* Returns the maximum linear speed in meters per sec.
*/
public double getMaxLinearSpeedMetersPerSec() {
return Constants.Drivetrain.MAX_LINEAR_SPEED;
return MAX_LINEAR_SPEED;
}

/**
* Returns the maximum angular speed in radians per sec.
*/
public double getMaxAngularSpeedRadPerSec() {
return Constants.Drivetrain.MAX_ANGULAR_SPEED;
return MAX_ANGULAR_SPEED;
}

/**
* Returns an array of module translations.
*/
public static Translation2d[] getModuleTranslations() {
return new Translation2d[]{
new Translation2d(Constants.Drivetrain.TRACK_WIDTH_X / 2.0, Constants.Drivetrain.TRACK_WIDTH_Y / 2.0),
new Translation2d(Constants.Drivetrain.TRACK_WIDTH_X / 2.0, -Constants.Drivetrain.TRACK_WIDTH_Y / 2.0),
new Translation2d(-Constants.Drivetrain.TRACK_WIDTH_X / 2.0, Constants.Drivetrain.TRACK_WIDTH_Y / 2.0),
new Translation2d(-Constants.Drivetrain.TRACK_WIDTH_X / 2.0, -Constants.Drivetrain.TRACK_WIDTH_Y / 2.0)
new Translation2d(TRACK_WIDTH_X / 2.0, TRACK_WIDTH_Y / 2.0),
new Translation2d(TRACK_WIDTH_X / 2.0, -TRACK_WIDTH_Y / 2.0),
new Translation2d(-TRACK_WIDTH_X / 2.0, TRACK_WIDTH_Y / 2.0),
new Translation2d(-TRACK_WIDTH_X / 2.0, -TRACK_WIDTH_Y / 2.0)
};
}
}
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
Loading

0 comments on commit 7d29459

Please sign in to comment.