Skip to content

Commit

Permalink
Merge branch 'main' into javadoc-everything
Browse files Browse the repository at this point in the history
  • Loading branch information
quackitsquinn authored Jan 24, 2024
2 parents 5025a34 + 3c9ff1d commit c826ce5
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 12 deletions.
13 changes: 13 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@

package frc.robot;

import edu.wpi.first.math.geometry.Translation2d;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
* constants. This class should not be used for any other purpose. All constants should be declared
Expand All @@ -27,4 +29,15 @@ public static class Controllers {
/** Driver station port number for the drive controller. */
public static final int DRIVER_CONTROLLER_PORT = 0;
}

public static class Drive {
/** Empty translation to prevent creating 2 Translation2ds every time the drive train stops. */
public static Translation2d EMPTY_TRANSLATION = new Translation2d();

/** The max speed the robot can go */
public static double MAX_SPEED = 1;

/** The max speed the robot can rotate */
public static double MAX_ANGULAR_SPEED = Math.PI / 2;
}
}
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,13 @@
import edu.wpi.first.wpilibj2.command.CommandScheduler;

public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private Command autonomousCommand;

private RobotContainer m_robotContainer;
private RobotContainer robotContainer;

@Override
public void robotInit() {
m_robotContainer = new RobotContainer();
robotContainer = new RobotContainer();
}

@Override
Expand All @@ -41,10 +41,10 @@ public void disabledExit() {}

@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
autonomousCommand = robotContainer.getAutonomousCommand();

if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
if (autonomousCommand != null) {
autonomousCommand.schedule();
}
}

Expand All @@ -56,8 +56,8 @@ public void autonomousExit() {}

@Override
public void teleopInit() {
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
if (autonomousCommand != null) {
autonomousCommand.cancel();
}
}

Expand Down
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,15 @@
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import java.io.File;
import java.io.IOException;
import swervelib.SwerveDrive;
import swervelib.parser.SwerveParser;

/** The subsystem that represents the drivetrain. */
public class Drive extends SubsystemBase {
SwerveDrive drive;
private SwerveDrive drive;

/** Creates a new Drive. */
public Drive() {
Expand Down Expand Up @@ -78,7 +79,8 @@ public void driveFieldOriented(double x, double y, double z) {

/** Stops all motors in the subsystem. */
public void stop() {
drive.drive(new Translation2d(), 0, false, false, new Translation2d());
drive.drive(
Constants.Drive.EMPTY_TRANSLATION, 0, false, false, Constants.Drive.EMPTY_TRANSLATION);
}

/** Points the wheels toward the inside and stops the wheels from moving in any direction. */
Expand All @@ -87,11 +89,11 @@ public void enterXMode() {
}

private double getMaximumSpeed() {
return 1; // TODO: move this to constants
return Constants.Drive.MAX_SPEED;
}

private double getMaximumAngularSpeed() {
return Math.PI / 2; // TODO: move this to constants
return Constants.Drive.MAX_ANGULAR_SPEED;
}

/** Runs every scheduler run. */
Expand Down

0 comments on commit c826ce5

Please sign in to comment.