Skip to content

Commit

Permalink
Update src/main/java/frc/robot/Constants.java
Browse files Browse the repository at this point in the history
  • Loading branch information
JetBluefan1 committed Nov 18, 2024
1 parent 662acc1 commit 7ecb1f0
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 7 deletions.
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,8 @@ public final class Constants {
public static final Measure<Mass> ROBOT_MASS = Pounds.of(125);
public static final Matter CHASSIS =
new Matter(new Translation3d(0, 0, Units.inchesToMeters(8)), ROBOT_MASS.in(Pounds));
public static final Measure<Time> LOOP_TIME = Seconds.of(0.13); // s, 20ms + 110ms sprk max velocity lag
public static final Measure<Time> LOOP_TIME =
Seconds.of(0.13); // s, 20ms + 110ms sprk max velocity lag
public static final Measure<Velocity<Distance>> MAX_SPEED = FeetPerSecond.of(14.5);

public static final class AutoConstants {
Expand All @@ -38,7 +39,7 @@ public static final class AutoConstants {

public static final class DrivebaseConstants {
// Hold time on motor brakes when disabled.
public static final double WHEEL_LOCK_TIME_SECS = 10; // seconds
public static final Measure<Time> WHEEL_LOCK_TIME_SECS = Seconds.of(10); // seconds
}

public static class OperatorConstants {
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

package frc.robot;

import static edu.wpi.first.units.Units.Seconds;

import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -74,7 +76,7 @@ public void disabledInit() {

@Override
public void disabledPeriodic() {
if (disabledTimer.hasElapsed(Constants.DrivebaseConstants.WHEEL_LOCK_TIME_SECS)) {
if (disabledTimer.hasElapsed(Constants.DrivebaseConstants.WHEEL_LOCK_TIME_SECS.in(Seconds))) {
m_robotContainer.setMotorBrake(false);
disabledTimer.stop();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@

package frc.robot.commands.drivebase;

import static edu.wpi.first.units.Units.Kilograms;
import static edu.wpi.first.units.Units.Seconds;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.subsystems.SwerveSubsystem;
import static edu.wpi.first.units.Units.Pounds;
import static edu.wpi.first.units.Units.Seconds;

import java.util.List;
import java.util.function.DoubleSupplier;
import swervelib.SwerveController;
Expand Down Expand Up @@ -68,7 +68,7 @@ public void execute() {
swerve.getFieldVelocity(),
swerve.getPose(),
Constants.LOOP_TIME.in(Seconds),
Constants.ROBOT_MASS.in(Pounds),
Constants.ROBOT_MASS.in(Kilograms),
List.of(Constants.CHASSIS),
swerve.getSwerveDriveConfiguration());
SmartDashboard.putNumber("LimitedTranslation", translation.getX());
Expand Down

0 comments on commit 7ecb1f0

Please sign in to comment.