Skip to content

Commit

Permalink
Moved Maximum Speed to Constants.java and Added ac Comment to Absolut…
Browse files Browse the repository at this point in the history
…eDriveAdv
  • Loading branch information
Technologyman00 committed Mar 24, 2024
1 parent e58d6bd commit 9ab6327
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 8 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ public final class Constants
public static final double ROBOT_MASS = (148 - 20.3) * 0.453592; // 32lbs * kg per pound
public static final Matter CHASSIS = new Matter(new Translation3d(0, 0, Units.inchesToMeters(8)), ROBOT_MASS);
public static final double LOOP_TIME = 0.13; //s, 20ms + 110ms sprk max velocity lag
public static final double MAX_SPEED = Units.feetToMeters(14.5); // Maximum speed of the robot in meters per second, used to limit acceleration.

public static final class AutonConstants
{
Expand Down
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,15 @@ public RobotContainer()
// Configure the trigger bindings
configureBindings();



// Applies deadbands and inverts controls because joysticks
// are back-right positive while robot
// controls are front-left positive
// left stick controls translation
// right stick controls the rotational velocity
// buttons are quick rotation positions to different ways to face
// WARNING: default buttons are on the same buttons as the ones defined in configureBindings
AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv(drivebase,
() -> -MathUtil.applyDeadband(driverXbox.getLeftY(),
OperatorConstants.LEFT_Y_DEADBAND),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
import frc.robot.Constants;
import frc.robot.Constants.AutonConstants;
import java.io.File;
import java.util.function.DoubleSupplier;
Expand All @@ -48,10 +49,6 @@ public class SwerveSubsystem extends SubsystemBase
* Swerve drive object.
*/
private final SwerveDrive swerveDrive;
/**
* Maximum speed of the robot in meters per second, used to limit acceleration.
*/
public double maximumSpeed = Units.feetToMeters(14.5);

/**
* Initialize {@link SwerveDrive} with the directory provided.
Expand All @@ -78,7 +75,7 @@ public SwerveSubsystem(File directory)
SwerveDriveTelemetry.verbosity = TelemetryVerbosity.HIGH;
try
{
swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed);
swerveDrive = new SwerveParser(directory).createSwerveDrive(Constants.MAX_SPEED);
// Alternative method if you don't want to supply the conversion factor via JSON files.
// swerveDrive = new SwerveParser(directory).createSwerveDrive(maximumSpeed, angleConversionFactor, driveConversionFactor);
} catch (Exception e)
Expand All @@ -98,7 +95,7 @@ public SwerveSubsystem(File directory)
*/
public SwerveSubsystem(SwerveDriveConfiguration driveCfg, SwerveControllerConfiguration controllerCfg)
{
swerveDrive = new SwerveDrive(driveCfg, controllerCfg, maximumSpeed);
swerveDrive = new SwerveDrive(driveCfg, controllerCfg, Constants.MAX_SPEED);
}

/**
Expand Down Expand Up @@ -516,7 +513,7 @@ public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, double headin
headingX,
headingY,
getHeading().getRadians(),
maximumSpeed);
Constants.MAX_SPEED);
}

/**
Expand All @@ -536,7 +533,7 @@ public ChassisSpeeds getTargetSpeeds(double xInput, double yInput, Rotation2d an
yInput,
angle.getRadians(),
getHeading().getRadians(),
maximumSpeed);
Constants.MAX_SPEED);
}

/**
Expand Down

0 comments on commit 9ab6327

Please sign in to comment.