Enforce leading/trailing zeros in Java numeric constants (#2105)

Enforce that integer literals must not have leading zeros and that floating point literals must have leading or trailing zeros in Java.
This commit is contained in:
Austin Shalit
2019-11-20 23:13:15 -05:00
committed by Peter Johnson
parent fa85fbfc1c
commit 4ebae17123
40 changed files with 92 additions and 72 deletions

View File

@@ -40,7 +40,7 @@ public final class Constants {
public static final int kEncoderCPR = 1024;
public static final double kEncoderDistancePerPulse =
// Distance units will be rotations
1. / (double) kEncoderCPR;
1.0 / (double) kEncoderCPR;
public static final int kShooterMotorPort = 4;
public static final int kFeederMotorPort = 5;
@@ -56,12 +56,12 @@ public final class Constants {
// On a real robot the feedforward constants should be empirically determined; these are
// reasonable guesses.
public static final double kSVolts = .05;
public static final double kSVolts = 0.05;
public static final double kVVoltSecondsPerRotation =
// Should have value 12V at free speed...
12. / kShooterFreeRPS;
12.0 / kShooterFreeRPS;
public static final double kFeederSpeed = .5;
public static final double kFeederSpeed = 0.5;
}
public static final class AutoConstants {

View File

@@ -103,7 +103,7 @@ public class RobotContainer {
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(.5))
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -78,7 +78,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the average of the two encoder readings
*/
public double getAverageEncoderDistance() {
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.;
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
}
/**

View File

@@ -36,7 +36,7 @@ public final class Constants {
public static final boolean kGyroReversed = false;
public static final double kStabilizationP = 1;
public static final double kStabilizationI = .5;
public static final double kStabilizationI = 0.5;
public static final double kStabilizationD = 0;
public static final double kTurnP = 1;

View File

@@ -65,7 +65,7 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(.5))
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
// Stabilize robot to drive straight with gyro when left bumper is held

View File

@@ -84,7 +84,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the average of the two encoder readings
*/
public double getAverageEncoderDistance() {
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.;
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
}
/**
@@ -127,7 +127,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the robot's heading in degrees, from 180 to 180
*/
public double getHeading() {
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (kGyroReversed ? -1. : 1.);
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (kGyroReversed ? -1.0 : 1.0);
}
/**
@@ -136,6 +136,6 @@ public class DriveSubsystem extends SubsystemBase {
* @return The turn rate of the robot, in degrees per second
*/
public double getTurnRate() {
return m_gyro.getRate() * (kGyroReversed ? -1. : 1.);
return m_gyro.getRate() * (kGyroReversed ? -1.0 : 1.0);
}
}

View File

@@ -42,7 +42,7 @@ public final class Constants {
public static final class AutoConstants {
public static final double kAutoDriveDistanceInches = 60;
public static final double kAutoBackupDistanceInches = 20;
public static final double kAutoDriveSpeed = .5;
public static final double kAutoDriveSpeed = 0.5;
}
public static final class OIConstants {

View File

@@ -105,7 +105,7 @@ public class RobotContainer {
.whenPressed(new InstantCommand(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
// While holding the shoulder button, drive at half speed
new JoystickButton(m_driverController, Button.kBumperRight.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(.5))
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -78,7 +78,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the average of the TWO encoder readings
*/
public double getAverageEncoderDistance() {
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.;
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
}
/**

View File

@@ -42,7 +42,7 @@ public final class Constants {
public static final class AutoConstants {
public static final double kAutoDriveDistanceInches = 60;
public static final double kAutoBackupDistanceInches = 20;
public static final double kAutoDriveSpeed = .5;
public static final double kAutoDriveSpeed = 0.5;
}
public static final class OIConstants {

View File

@@ -20,7 +20,7 @@ public class HalveDriveSpeed extends CommandBase {
@Override
public void initialize() {
m_drive.setMaxOutput(.5);
m_drive.setMaxOutput(0.5);
}
@Override

View File

@@ -78,7 +78,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the average of the TWO encoder readings
*/
public double getAverageEncoderDistance() {
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.;
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
}
/**

View File

@@ -30,12 +30,12 @@ public final class Constants {
public static final boolean kLeftEncoderReversed = false;
public static final boolean kRightEncoderReversed = true;
public static final double kTrackwidthMeters = .6;
public static final double kTrackwidthMeters = 0.6;
public static final DifferentialDriveKinematics kDriveKinematics =
new DifferentialDriveKinematics(kTrackwidthMeters);
public static final int kEncoderCPR = 1024;
public static final double kWheelDiameterMeters = .15;
public static final double kWheelDiameterMeters = 0.15;
public static final double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterMeters * Math.PI) / (double) kEncoderCPR;
@@ -48,11 +48,11 @@ public final class Constants {
// The RobotPy Characterization Toolsuite provides a convenient tool for obtaining these
// values for your robot.
public static final double ksVolts = 1;
public static final double kvVoltSecondsPerMeter = .8;
public static final double kaVoltSecondsSquaredPerMeter = .15;
public static final double kvVoltSecondsPerMeter = 0.8;
public static final double kaVoltSecondsSquaredPerMeter = 0.15;
// Example value only - as above, this must be tuned for your drive!
public static final double kPDriveVel = .5;
public static final double kPDriveVel = 0.5;
}
public static final class OIConstants {
@@ -69,6 +69,6 @@ public final class Constants {
// Reasonable baseline values for a RAMSETE follower in units of meters and seconds
public static final double kRamseteB = 2;
public static final double kRamseteZeta = .7;
public static final double kRamseteZeta = 0.7;
}
}

View File

@@ -79,7 +79,7 @@ public class RobotContainer {
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(.5))
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -137,7 +137,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the average of the two encoder readings
*/
public double getAverageEncoderDistance() {
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.;
return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2.0;
}
/**
@@ -180,7 +180,7 @@ public class DriveSubsystem extends SubsystemBase {
* @return the robot's heading in degrees, from 180 to 180
*/
public double getHeading() {
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (kGyroReversed ? -1. : 1.);
return Math.IEEEremainder(m_gyro.getAngle(), 360) * (kGyroReversed ? -1.0 : 1.0);
}
/**
@@ -189,6 +189,6 @@ public class DriveSubsystem extends SubsystemBase {
* @return The turn rate of the robot, in degrees per second
*/
public double getTurnRate() {
return m_gyro.getRate() * (kGyroReversed ? -1. : 1.);
return m_gyro.getRate() * (kGyroReversed ? -1.0 : 1.0);
}
}