Indentation, whitespace, and linting changes

This commit is contained in:
2024-01-09 22:17:24 -05:00
parent 1e2af3716d
commit 1f76cb39ea
4 changed files with 137 additions and 135 deletions

View File

@@ -3,19 +3,19 @@ package frc.robot.constants;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
public final class AutoConstants {
public static final double kMaxSpeedMetersPerSecond = 3.895; // max capable = 4.6
public static final double kMaxAccelerationMetersPerSecondSquared = 3; // max capable = 7.4
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
public static final double kMaxSpeedMetersPerSecond = 3.895; // max capable = 4.6
public static final double kMaxAccelerationMetersPerSecondSquared = 3; // max capable = 7.4
public static final double kMaxAngularSpeedRadiansPerSecond = Math.PI;
public static final double kMaxAngularSpeedRadiansPerSecondSquared = Math.PI;
public static final double kPXController = 1.05;
public static final double kPYController = 1.05;
public static final double kPThetaController = 0.95; // needs to be separate from heading control
public static final double kPXController = 1.05;
public static final double kPYController = 1.05;
public static final double kPThetaController = 0.95; // needs to be separate from heading control
public static final double kPHeadingController = 0.02; // for heading control NOT PATHING
public static final double kDHeadingController = 0.0025;
public static final double kPHeadingController = 0.02; // for heading control NOT PATHING
public static final double kDHeadingController = 0.0025;
// Constraint for the motion profiled robot angle controller
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
}
// Constraint for the motion profiled robot angle controller
public static final TrapezoidProfile.Constraints kThetaControllerConstraints = new TrapezoidProfile.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
}

View File

@@ -5,47 +5,47 @@ import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.util.Units;
public final class DrivetrainConstants {
// Driving Parameters - Note that these are not the maximum capable speeds of
// the robot, rather the allowed maximum speeds
public static final double kMaxSpeedMetersPerSecond = 4.6;
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
// Driving Parameters - Note that these are not the maximum capable speeds of
// the robot, rather the allowed maximum speeds
public static final double kMaxSpeedMetersPerSecond = 4.6;
public static final double kMaxAngularSpeed = 2 * Math.PI; // radians per second
public static final double kDirectionSlewRate = 2.4; // radians per second
public static final double kMagnitudeSlewRate = 3.2; // percent per second (1 = 100%)
public static final double kRotationalSlewRate = 4.0; // percent per second (1 = 100%)
public static final double kDirectionSlewRate = 2.4; // radians per second
public static final double kMagnitudeSlewRate = 3.2; // percent per second (1 = 100%)
public static final double kRotationalSlewRate = 4.0; // percent per second (1 = 100%)
// Chassis configuration
public static final double kTrackWidth = Units.inchesToMeters(26.5-1.75*2);
// Distance between centers of right and left wheels on robot
public static final double kWheelBase = Units.inchesToMeters(32.3-1.75*2);
// Distance between front and back wheels on robot
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
// Chassis configuration
public static final double kTrackWidth = Units.inchesToMeters(26.5-1.75*2);
// Distance between centers of right and left wheels on robot
public static final double kWheelBase = Units.inchesToMeters(32.3-1.75*2);
// Distance between front and back wheels on robot
public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
new Translation2d(kWheelBase / 2, -kTrackWidth / 2),
new Translation2d(-kWheelBase / 2, kTrackWidth / 2),
new Translation2d(-kWheelBase / 2, -kTrackWidth / 2));
// Angular offsets of the modules relative to the chassis in radians
public static final double kFrontLeftChassisAngularOffset = -Math.PI / 2;
public static final double kFrontRightChassisAngularOffset = 0;
public static final double kBackLeftChassisAngularOffset = Math.PI;
public static final double kBackRightChassisAngularOffset = Math.PI / 2;
// Angular offsets of the modules relative to the chassis in radians
public static final double kFrontLeftChassisAngularOffset = -Math.PI / 2;
public static final double kFrontRightChassisAngularOffset = 0;
public static final double kBackLeftChassisAngularOffset = Math.PI;
public static final double kBackRightChassisAngularOffset = Math.PI / 2;
// SPARK MAX CAN IDs
public static final int kFrontLeftDrivingCanId = 1;
public static final int kRearLeftDrivingCanId = 3;
public static final int kFrontRightDrivingCanId = 4;
public static final int kRearRightDrivingCanId = 2;
// SPARK MAX CAN IDs
public static final int kFrontLeftDrivingCanId = 1;
public static final int kRearLeftDrivingCanId = 3;
public static final int kFrontRightDrivingCanId = 4;
public static final int kRearRightDrivingCanId = 2;
public static final int kFrontLeftTurningCanId = 5;
public static final int kRearLeftTurningCanId = 7;
public static final int kFrontRightTurningCanId = 8;
public static final int kRearRightTurningCanId = 6;
public static final int kFrontLeftTurningCanId = 5;
public static final int kRearLeftTurningCanId = 7;
public static final int kFrontRightTurningCanId = 8;
public static final int kRearRightTurningCanId = 6;
public static final double kTurnToleranceDeg = 0;
public static final double kTurnRateToleranceDegPerS = 0;
public static final double kTurnToleranceDeg = 0;
public static final double kTurnRateToleranceDegPerS = 0;
public static final boolean kGyroReversed = true;
public static final boolean kGyroReversed = true;
public static final double kRobotStartOffset = 180;
}
public static final double kRobotStartOffset = 180;
}

View File

@@ -4,51 +4,51 @@ import com.revrobotics.CANSparkBase.IdleMode;
public class ModuleConstants {
// The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
// robot that drives faster).
public static final int kDrivingMotorPinionTeeth = 14;
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
// robot that drives faster).
public static final int kDrivingMotorPinionTeeth = 14;
// Invert the turning encoder, since the output shaft rotates in the opposite direction of
// the steering motor in the MAXSwerve Module.
public static final boolean kTurningEncoderInverted = true;
// Invert the turning encoder, since the output shaft rotates in the opposite direction of
// the steering motor in the MAXSwerve Module.
public static final boolean kTurningEncoderInverted = true;
// Calculations required for driving motor conversion factors and feed forward
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
public static final double kWheelDiameterMeters = 0.0762;
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
/ kDrivingMotorReduction;
// Calculations required for driving motor conversion factors and feed forward
public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60;
public static final double kWheelDiameterMeters = 0.0762;
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
// 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
public static final double kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15);
public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)
/ kDrivingMotorReduction;
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
/ kDrivingMotorReduction; // meters
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
/ kDrivingMotorReduction) / 60.0; // meters per second
public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math.PI)
/ kDrivingMotorReduction; // meters
public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math.PI)
/ kDrivingMotorReduction) / 60.0; // meters per second
public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second
public static final double kTurningEncoderPositionFactor = (2 * Math.PI); // radians
public static final double kTurningEncoderVelocityFactor = (2 * Math.PI) / 60.0; // radians per second
public static final double kTurningEncoderPositionPIDMinInput = 0; // radians
public static final double kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor; // radians
public static final double kTurningEncoderPositionPIDMinInput = 0; // radians
public static final double kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor; // radians
public static final double kDrivingP = 0.04;
public static final double kDrivingI = 0;
public static final double kDrivingD = 0;
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
public static final double kDrivingMinOutput = -1;
public static final double kDrivingMaxOutput = 1;
public static final double kDrivingP = 0.04;
public static final double kDrivingI = 0;
public static final double kDrivingD = 0;
public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps;
public static final double kDrivingMinOutput = -1;
public static final double kDrivingMaxOutput = 1;
public static final double kTurningP = 1;
public static final double kTurningI = 0;
public static final double kTurningD = 0;
public static final double kTurningFF = 0;
public static final double kTurningMinOutput = -1;
public static final double kTurningMaxOutput = 1;
public static final double kTurningP = 1;
public static final double kTurningI = 0;
public static final double kTurningD = 0;
public static final double kTurningFF = 0;
public static final double kTurningMinOutput = -1;
public static final double kTurningMaxOutput = 1;
public static final IdleMode kDrivingMotorIdleMode = IdleMode.kBrake;
public static final IdleMode kTurningMotorIdleMode = IdleMode.kBrake;
public static final IdleMode kDrivingMotorIdleMode = IdleMode.kBrake;
public static final IdleMode kTurningMotorIdleMode = IdleMode.kBrake;
public static final int kDrivingMotorCurrentLimit = 60; // amps
public static final int kTurningMotorCurrentLimit = 30; // amps
public static final int kDrivingMotorCurrentLimit = 60; // amps
public static final int kTurningMotorCurrentLimit = 30; // amps
}