Skip to content

Commit

Permalink
Basic Swerve YAGSL implementation
Browse files Browse the repository at this point in the history
  • Loading branch information
BrownGenius committed Jan 19, 2024
1 parent 38e847d commit c7a540c
Show file tree
Hide file tree
Showing 5 changed files with 151 additions and 1 deletion.
21 changes: 20 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,32 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.drive.DriveCommand;
import frc.robot.subsystems.drive.DriveSwerveYAGSL;

public class RobotContainer {
CommandXboxController controller = new CommandXboxController(0);
DriveSwerveYAGSL drive = new DriveSwerveYAGSL();

public RobotContainer() {
configureBindings();
}

private void configureBindings() {}
private void configureBindings() {
drive.setDefaultCommand(
new DriveCommand(
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> -controller.getRightX()));

controller
.start()
.onTrue(
new InstantCommand(() -> drive.setFieldOrientedDrive(!drive.isFieldOrientedDrive())));
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
34 changes: 34 additions & 0 deletions src/main/java/frc/robot/commands/drive/DriveCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package frc.robot.commands.drive;

import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.drive.DriveBase;
import java.util.function.DoubleSupplier;

public class DriveCommand extends Command {
DriveBase drive;
DoubleSupplier speedX;
DoubleSupplier speedY;
DoubleSupplier rot;

public DriveCommand(
DriveBase drive, DoubleSupplier speedX, DoubleSupplier speedY, DoubleSupplier rot) {
this.drive = drive;
this.speedX = speedX;
this.speedY = speedY;
this.rot = rot;

addRequirements(drive);
}

@Override
public void execute() {
ChassisSpeeds speeds =
new ChassisSpeeds(
speedX.getAsDouble() * drive.getMaxLinearSpeed(),
speedY.getAsDouble() * drive.getMaxLinearSpeed(),
rot.getAsDouble() * drive.getMaxAngularSpeed());

drive.runVelocity(speeds);
}
}
26 changes: 26 additions & 0 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
package frc.robot.subsystems.drive;

import edu.wpi.first.math.kinematics.ChassisSpeeds;

public interface Drive {
/**
* Sets the desired chassis speed
*
* @param velocity specifies the setpoint velocity for the chassis
*/
public void runVelocity(ChassisSpeeds velocity);

/**
* This returns the robot's max linear speed in meter/sec
*
* @return speed in meter/sec
*/
public double getMaxLinearSpeed();

/**
* This returns the robot's max angular speed in radian/sec
*
* @return speed in radian/sec
*/
public double getMaxAngularSpeed();
}
19 changes: 19 additions & 0 deletions src/main/java/frc/robot/subsystems/drive/DriveBase.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
package frc.robot.subsystems.drive;

import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class DriveBase extends SubsystemBase implements Drive {
@Override
public void runVelocity(ChassisSpeeds velocity) {}

@Override
public double getMaxLinearSpeed() {
return 0;
}

@Override
public double getMaxAngularSpeed() {
return 0;
}
}
52 changes: 52 additions & 0 deletions src/main/java/frc/robot/subsystems/drive/DriveSwerveYAGSL.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
package frc.robot.subsystems.drive;

import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Filesystem;
import java.io.File;
import swervelib.SwerveDrive;
import swervelib.parser.SwerveParser;

public class DriveSwerveYAGSL extends DriveBase {
private final double maximumSpeed =
Units.feetToMeters(4.5); // * TODO: Calculate actual max speed */
private final File swerveJsonDirectory =
new File(Filesystem.getDeployDirectory(), "swervePracticeBot");
private SwerveDrive swerveDrive;
private boolean fieldOrientedDrive = false;

public DriveSwerveYAGSL() {
try {
swerveDrive = new SwerveParser(swerveJsonDirectory).createSwerveDrive(maximumSpeed);
} catch (Exception e) {
throw new RuntimeException(e);
}
}

@Override
public void runVelocity(ChassisSpeeds velocity) {
if (fieldOrientedDrive) {
swerveDrive.driveFieldOriented(velocity);
} else {
swerveDrive.drive(velocity);
}
}

@Override
public double getMaxLinearSpeed() {
return swerveDrive.getMaximumVelocity();
}

@Override
public double getMaxAngularSpeed() {
return swerveDrive.getMaximumAngularVelocity();
}

public void setFieldOrientedDrive(boolean enable) {
fieldOrientedDrive = enable;
}

public boolean isFieldOrientedDrive() {
return fieldOrientedDrive;
}
}

0 comments on commit c7a540c

Please sign in to comment.