Skip to content

Commit

Permalink
Enforce leading/trailing zeros in Java numeric constants (#2105)
Browse files Browse the repository at this point in the history
Enforce that integer literals must not have leading zeros and that floating point literals must have leading or trailing zeros in Java.
  • Loading branch information
AustinShalit authored and PeterJohnson committed Nov 21, 2019
1 parent fa85fbf commit 4ebae17
Show file tree
Hide file tree
Showing 40 changed files with 92 additions and 72 deletions.
20 changes: 20 additions & 0 deletions styleguide/checkstyle.xml
Expand Up @@ -51,6 +51,26 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN"
<property name="message"
value="Avoid using corresponding octal or Unicode escape." />
</module>
<module name="IllegalTokenText">
<property name="tokens"
value="NUM_INT,NUM_LONG"/>
<property name="format"
value="^0[^lx]"/>
<property name="ignoreCase"
value="true"/>
<property name="message"
value="Forbid leading zeros in an integer literal, other than zero and a hex literal." />
</module>
<module name="IllegalTokenText">
<property name="tokens"
value="NUM_DOUBLE,NUM_FLOAT"/>
<property name="format"
value="(^\.|\.$)"/>
<property name="ignoreCase"
value="true"/>
<property name="message"
value="Must use leading and trailing zero in floating point numbers." />
</module>
<module name="AvoidEscapedUnicodeCharacters">
<property name="allowEscapesForControlCharacters"
value="true" />
Expand Down
Expand Up @@ -124,7 +124,7 @@ public void execute() {

@Override
public void end(boolean interrupted) {
m_useOutput.accept(0., new State());
m_useOutput.accept(0.0, new State());
}

/**
Expand Down
Expand Up @@ -30,7 +30,7 @@ public TrapezoidProfileSubsystem(TrapezoidProfile.Constraints constraints,
double initialPosition) {
m_constraints = constraints;
m_state = new TrapezoidProfile.State(initialPosition, 0);
m_period = .02;
m_period = 0.02;
}

/**
Expand Down
Expand Up @@ -23,10 +23,10 @@ void notifierCommandScheduleTest() {

Counter counter = new Counter();

NotifierCommand command = new NotifierCommand(counter::increment, .01);
NotifierCommand command = new NotifierCommand(counter::increment, 0.01);

scheduler.schedule(command);
Timer.delay(.25);
Timer.delay(0.25);
scheduler.cancel(command);

assertTrue(counter.m_counter > 10, "Should have hit at least 10 triggers");
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
Expand Up @@ -84,7 +84,7 @@ public Counter(final Mode mode) {
m_upSource = null;
m_downSource = null;

setMaxPeriod(.5);
setMaxPeriod(0.5);

HAL.report(tResourceType.kResourceType_Counter, m_index + 1, mode.value + 1);
SendableRegistry.addLW(this, "Counter", m_index);
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java
Expand Up @@ -38,7 +38,7 @@ public class DMC60 extends PWMSpeedController {
public DMC60(final int channel) {
super(channel);

setBounds(2.004, 1.52, 1.50, 1.48, .997);
setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java
Expand Up @@ -38,7 +38,7 @@ public class Jaguar extends PWMSpeedController {
public Jaguar(final int channel) {
super(channel);

setBounds(2.31, 1.55, 1.507, 1.454, .697);
setBounds(2.31, 1.55, 1.507, 1.454, 0.697);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
Expand Up @@ -36,7 +36,7 @@ public class PWMSparkMax extends PWMSpeedController {
public PWMSparkMax(final int channel) {
super(channel);

setBounds(2.003, 1.55, 1.50, 1.46, .999);
setBounds(2.003, 1.55, 1.50, 1.46, 0.999);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
Expand Up @@ -38,7 +38,7 @@ public class PWMTalonSRX extends PWMSpeedController {
public PWMTalonSRX(final int channel) {
super(channel);

setBounds(2.004, 1.52, 1.50, 1.48, .997);
setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
Expand Up @@ -38,7 +38,7 @@ public class PWMVictorSPX extends PWMSpeedController {
public PWMVictorSPX(final int channel) {
super(channel);

setBounds(2.004, 1.52, 1.50, 1.48, .997);
setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
4 changes: 2 additions & 2 deletions wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java
Expand Up @@ -178,15 +178,15 @@ public void drive(double outputMagnitude, double curve) {
double value = Math.log(-curve);
double ratio = (value - m_sensitivity) / (value + m_sensitivity);
if (ratio == 0) {
ratio = .0000000001;
ratio = 0.0000000001;
}
leftOutput = outputMagnitude / ratio;
rightOutput = outputMagnitude;
} else if (curve > 0) {
double value = Math.log(curve);
double ratio = (value - m_sensitivity) / (value + m_sensitivity);
if (ratio == 0) {
ratio = .0000000001;
ratio = 0.0000000001;
}
leftOutput = outputMagnitude;
rightOutput = outputMagnitude / ratio;
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java
Expand Up @@ -33,7 +33,7 @@ public class SD540 extends PWMSpeedController {
* Common initialization code called by all constructors.
*/
protected void initSD540() {
setBounds(2.05, 1.55, 1.50, 1.44, .94);
setBounds(2.05, 1.55, 1.50, 1.44, 0.94);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java
Expand Up @@ -23,7 +23,7 @@ public class Servo extends PWM {
private static final double kMinServoAngle = 0.0;

protected static final double kDefaultMaxServoPWM = 2.4;
protected static final double kDefaultMinServoPWM = .6;
protected static final double kDefaultMinServoPWM = 0.6;

/**
* Constructor.<br>
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java
Expand Up @@ -33,7 +33,7 @@ public class Spark extends PWMSpeedController {
* Common initialization code called by all constructors.
*/
protected void initSpark() {
setBounds(2.003, 1.55, 1.50, 1.46, .999);
setBounds(2.003, 1.55, 1.50, 1.46, 0.999);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java
Expand Up @@ -38,7 +38,7 @@ public class Talon extends PWMSpeedController {
public Talon(final int channel) {
super(channel);

setBounds(2.037, 1.539, 1.513, 1.487, .989);
setBounds(2.037, 1.539, 1.513, 1.487, 0.989);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
2 changes: 1 addition & 1 deletion wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java
Expand Up @@ -38,7 +38,7 @@ public class VictorSP extends PWMSpeedController {
public VictorSP(final int channel) {
super(channel);

setBounds(2.004, 1.52, 1.50, 1.48, .997);
setBounds(2.004, 1.52, 1.50, 1.48, 0.997);
setPeriodMultiplier(PeriodMultiplier.k1X);
setSpeed(0.0);
setZeroLatch();
Expand Down
Expand Up @@ -43,7 +43,7 @@ void integralGainOutputTest() {
double out = 0;

for (int i = 0; i < 5; i++) {
out = m_controller.calculate(.025, 0);
out = m_controller.calculate(0.025, 0);
}

assertEquals(-0.5 * m_controller.getPeriod(), out, 1e-5);
Expand Down
Expand Up @@ -40,7 +40,7 @@ public static final class ShooterConstants {
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;
Expand All @@ -56,12 +56,12 @@ public static final class ShooterConstants {

// 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 {
Expand Down
Expand Up @@ -103,7 +103,7 @@ private void configureButtonBindings() {

// 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));
}

Expand Down
Expand Up @@ -78,7 +78,7 @@ public void resetEncoders() {
* @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;
}

/**
Expand Down
Expand Up @@ -36,7 +36,7 @@ public static final class DriveConstants {
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;
Expand Down
Expand Up @@ -65,7 +65,7 @@ public 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
Expand Down
Expand Up @@ -84,7 +84,7 @@ public void resetEncoders() {
* @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;
}

/**
Expand Down Expand Up @@ -127,7 +127,7 @@ public void zeroHeading() {
* @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);
}

/**
Expand All @@ -136,6 +136,6 @@ public double getHeading() {
* @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);
}
}
Expand Up @@ -42,7 +42,7 @@ public static final class HatchConstants {
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 {
Expand Down
Expand Up @@ -105,7 +105,7 @@ private void configureButtonBindings() {
.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));
}

Expand Down
Expand Up @@ -78,7 +78,7 @@ public void resetEncoders() {
* @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;
}

/**
Expand Down
Expand Up @@ -42,7 +42,7 @@ public static final class HatchConstants {
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 {
Expand Down
Expand Up @@ -20,7 +20,7 @@ public HalveDriveSpeed(DriveSubsystem drive) {

@Override
public void initialize() {
m_drive.setMaxOutput(.5);
m_drive.setMaxOutput(0.5);
}

@Override
Expand Down
Expand Up @@ -78,7 +78,7 @@ public void resetEncoders() {
* @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;
}

/**
Expand Down
Expand Up @@ -30,12 +30,12 @@ public static final class DriveConstants {
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;
Expand All @@ -48,11 +48,11 @@ public static final class DriveConstants {
// 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 {
Expand All @@ -69,6 +69,6 @@ public static final class AutoConstants {

// 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;
}
}
Expand Up @@ -79,7 +79,7 @@ public 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));

}
Expand Down
Expand Up @@ -137,7 +137,7 @@ public void resetEncoders() {
* @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;
}

/**
Expand Down Expand Up @@ -180,7 +180,7 @@ public void zeroHeading() {
* @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);
}

/**
Expand All @@ -189,6 +189,6 @@ public double getHeading() {
* @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);
}
}

0 comments on commit 4ebae17

Please sign in to comment.