Skip to content

Commit

Permalink
fix parameter naming
Browse files Browse the repository at this point in the history
switch to _ instead of Param
  • Loading branch information
JayAgra committed Aug 14, 2023
1 parent 4947e21 commit f4f525d
Show file tree
Hide file tree
Showing 39 changed files with 140 additions and 140 deletions.
4 changes: 2 additions & 2 deletions src/main/java/com/team766/config/ConfigValue.java
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,9 @@ public String parseJsonValue(final Object configValue) {
class EnumConfigValue<E extends Enum<E>> extends AbstractConfigValue<E> {
Class<E> enumClass;

protected EnumConfigValue(final Class<E> enumClassParam, final String key) {
protected EnumConfigValue(final Class<E> enumClass_, final String key) {
super(key);
this.enumClass = enumClassParam;
this.enumClass = enumClass_;
}

@Override
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/com/team766/controllers/PIDController.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,8 @@ public PIDController(final double P, final double I, final double D, final doubl
((SetValueProvider<Double>) Kff).set(FF);
}

private void setTimeProvider(final TimeProviderI timeProviderParam) {
this.timeProvider = timeProviderParam;
private void setTimeProvider(final TimeProviderI timeProvider_) {
this.timeProvider = timeProvider_;
lastTime = timeProvider.get();
}

Expand Down Expand Up @@ -123,27 +123,27 @@ public PIDController(final ValueProvider<Double> P, final ValueProvider<Double>
* @param timeProvider
*/
public PIDController(final double P, final double I, final double D, final double threshold,
final TimeProviderI timeProviderParam) {
final TimeProviderI timeProvider_) {
Kp = new SetValueProvider<Double>(P);
Ki = new SetValueProvider<Double>(I);
Kd = new SetValueProvider<Double>(D);
Kff = new SetValueProvider<Double>();
maxoutput_low = new SetValueProvider<Double>();
maxoutput_high = new SetValueProvider<Double>();
endthreshold = new SetValueProvider<Double>(threshold);
setTimeProvider(timeProviderParam);
setTimeProvider(timeProvider_);
}

public PIDController(final double P, final double I, final double D, final double FF,
final double threshold, final TimeProviderI timeProviderParam) {
final double threshold, final TimeProviderI timeProvider_) {
Kp = new SetValueProvider<Double>(P);
Ki = new SetValueProvider<Double>(I);
Kd = new SetValueProvider<Double>(D);
Kff = new SetValueProvider<Double>(FF);
maxoutput_low = new SetValueProvider<Double>();
maxoutput_high = new SetValueProvider<Double>();
endthreshold = new SetValueProvider<Double>(threshold);
setTimeProvider(timeProviderParam);
setTimeProvider(timeProvider_);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,9 @@ public class WPILibCommandProcedure extends Procedure {
* @param requirements This Procedure will take ownership of the Mechanisms
* given here during the time it is executing.
*/
public WPILibCommandProcedure(final Command commandParam, final Mechanism... requirementsParam) {
this.command = commandParam;
this.requirements = requirementsParam;
public WPILibCommandProcedure(final Command command_, final Mechanism... requirements_) {
this.command = command_;
this.requirements = requirements_;
}

@Override
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/com/team766/hal/DoubleSolenoid.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@ public enum State {
Forward, Neutral, Backward
}

public DoubleSolenoid(final SolenoidController forwardParam, final SolenoidController backParam) {
this.forward = forwardParam;
this.back = backParam;
public DoubleSolenoid(final SolenoidController forward_, final SolenoidController back_) {
this.forward = forward_;
this.back = back_;

set(State.Neutral);
}
Expand Down
18 changes: 9 additions & 9 deletions src/main/java/com/team766/hal/LocalMotorController.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@ public class LocalMotorController implements MotorController {
private double setpoint = 0.0;
private MotorController leader = null;

public LocalMotorController(String configPrefix, final BasicMotorController motorParam,
final ControlInputReader sensorParam) {
this.motor = motorParam;
this.sensor = sensorParam;
public LocalMotorController(String configPrefix, final BasicMotorController motor_,
final ControlInputReader sensor_) {
this.motor = motor_;
this.sensor = sensor_;

if (!configPrefix.endsWith(".")) {
configPrefix += ".";
Expand Down Expand Up @@ -198,13 +198,13 @@ public ControlMode getControlMode() {
}

@Override
public void follow(final MotorController leaderParam) {
if (leaderParam == null) {
public void follow(final MotorController leader_) {
if (leader_ == null) {
throw new IllegalArgumentException("leader argument to follow() is null");
}
// TODO: detect if this.motor is a MotorController, and delegate to its follow() method if so.
this.controlMode = ControlMode.Follower;
this.leader = leaderParam;
this.leader = leader_;
}

@Override
Expand Down Expand Up @@ -244,8 +244,8 @@ public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) {
}

@Override
public void setSensorInverted(final boolean invertedParam) {
this.sensorInverted = invertedParam;
public void setSensorInverted(final boolean inverted_) {
this.sensorInverted = inverted_;
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@ public class MotorControllerWithSensorScale implements MotorController {
private MotorController delegate;
private double scale;

public MotorControllerWithSensorScale(final MotorController delegateParam, final double scaleParam) {
this.delegate = delegateParam;
this.scale = scaleParam;
public MotorControllerWithSensorScale(final MotorController delegate_, final double scale_) {
this.delegate = delegate_;
this.scale = scale_;
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/MultiSolenoid.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ public class MultiSolenoid implements SolenoidController {
private SolenoidController[] solenoids;
private boolean state;

public MultiSolenoid(final SolenoidController... solenoidsParam) {
this.solenoids = solenoidsParam;
public MultiSolenoid(final SolenoidController... solenoids_) {
this.solenoids = solenoids_;

set(false);
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/mock/MockCamera.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@ public Mat getImage() {
return Imgcodecs.imread(nextImage);
}

public void setNextImage(final String nextImageParam) {
this.nextImage = this.getClass().getClassLoader().getResource(nextImageParam).getPath();
public void setNextImage(final String nextImage_) {
this.nextImage = this.getClass().getClassLoader().getResource(nextImage_).getPath();
}

}
12 changes: 6 additions & 6 deletions src/main/java/com/team766/hal/mock/MockEncoder.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,17 +41,17 @@ public double getRate() {
return this.rate;
}

public void setDistance(final double distanceParam) {
this.distance = distanceParam;
public void setDistance(final double distance_) {
this.distance = distance_;
}

public void setRate(final double rateParam) {
this.rate = rateParam;
public void setRate(final double rate_) {
this.rate = rate_;
}

@Override
public void setDistancePerPulse(final double distancePerPulseParam) {
this.distancePerPulse = distancePerPulseParam;
public void setDistancePerPulse(final double distancePerPulse_) {
this.distancePerPulse = distancePerPulse_;
}

}
16 changes: 8 additions & 8 deletions src/main/java/com/team766/hal/mock/MockGyro.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,20 +33,20 @@ public double getRoll() {
return roll;
}

public void setAngle(final double angleParam) {
this.angle = angleParam;
public void setAngle(final double angle_) {
this.angle = angle_;
}

public void setRate(final double rateParam) {
this.rate = rateParam;
public void setRate(final double rate_) {
this.rate = rate_;
}

public void setPitch(final double pitchParam) {
this.pitch = pitchParam;
public void setPitch(final double pitch_) {
this.pitch = pitch_;
}

public void setRoll(final double rollParam) {
this.roll = rollParam;
public void setRoll(final double roll_) {
this.roll = roll_;
}

}
12 changes: 6 additions & 6 deletions src/main/java/com/team766/hal/mock/MockPositionSensor.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,16 +23,16 @@ public double getHeading() {
return heading;
}

public void setX(final double xParam) {
this.x = xParam;
public void setX(final double x_) {
this.x = x_;
}

public void setY(final double yParam) {
this.y = yParam;
public void setY(final double y_) {
this.y = y_;
}

public void setHeading(final double headingParam) {
this.heading = headingParam;
public void setHeading(final double heading_) {
this.heading = heading_;
}

}
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/simulator/AnalogInput.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ public class AnalogInput implements AnalogInputReader {

private final int channel;

public AnalogInput(final int channelParam) {
this.channel = channelParam;
public AnalogInput(final int channel_) {
this.channel = channel_;
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/simulator/DigitalInput.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ public class DigitalInput implements DigitalInputReader {

private final int channel;

public DigitalInput(final int channelParam) {
this.channel = channelParam;
public DigitalInput(final int channel_) {
this.channel = channel_;
}

public boolean get() {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/simulator/Encoder.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ public double getRate() {
}

@Override
public void setDistancePerPulse(final double distancePerPulseParam) {
this.distancePerPulse = distancePerPulseParam;
public void setDistancePerPulse(final double distancePerPulse_) {
this.distancePerPulse = distancePerPulse_;
}

public void set(final int tick) {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/simulator/Relay.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ public class Relay implements RelayOutput {

private int channel;

public Relay(final int channelParam) {
this.channel = channelParam;
public Relay(final int channel_) {
this.channel = channel_;
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ class SimBasicMotorController implements BasicMotorController {
this(ProgramInterface.canMotorControllerChannels[address]);
}

SimBasicMotorController(final ProgramInterface.CANMotorControllerCommunication channelParam) {
this.channel = channelParam;
SimBasicMotorController(final ProgramInterface.CANMotorControllerCommunication channel_) {
this.channel = channel_;
}

@Override
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/hal/simulator/Solenoid.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ public class Solenoid implements SolenoidController {

private int channel;

public Solenoid(final int channelParam) {
this.channel = channelParam;
public Solenoid(final int channel_) {
this.channel = channel_;
}

public void set(final boolean on) {
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/com/team766/hal/simulator/VrConnector.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,11 @@ private static class CANPortMapping {
public final int motorCommandMessageDataIndex;
public final int sensorFeedbackMessageDataIndex;

CANPortMapping(final int canIdParam, final int motorCommandMessageDataIndexParam,
final int sensorFeedbackMessageDataIndexParam) {
this.canId = canIdParam;
this.motorCommandMessageDataIndex = motorCommandMessageDataIndexParam;
this.sensorFeedbackMessageDataIndex = sensorFeedbackMessageDataIndexParam;
CANPortMapping(final int canId_, final int motorCommandMessageDataIndex_,
final int sensorFeedbackMessageDataIndex_) {
this.canId = canId_;
this.motorCommandMessageDataIndex = motorCommandMessageDataIndex_;
this.sensorFeedbackMessageDataIndex = sensorFeedbackMessageDataIndex_;
}
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/team766/hal/wpilib/Relay.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public void set(final com.team766.hal.RelayOutput.Value value) {
wpi_value = edu.wpi.first.wpilibj.Relay.Value.kReverse;
break;
default:
LoggerExceptionUtils.logException(new UnsupportedOperationException("invalid relay output provided. provided value: " + mode));
LoggerExceptionUtils.logException(new UnsupportedOperationException("invalid relay output provided. provided value: " + value));
break;
}
if (wpi_value == null) {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/library/RateLimiter.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@ public class RateLimiter {
private final double periodSeconds;
private double nextTime = 0;

public RateLimiter(final double periodSecondsParam) {
this.periodSeconds = periodSecondsParam;
public RateLimiter(final double periodSeconds_) {
this.periodSeconds = periodSeconds_;
}

public boolean next() {
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/com/team766/math/IirFilter.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@ public class IirFilter implements Filter {
private double decay;
private double value;

public IirFilter(final double decayParam, final double initialValueParam) {
this.decay = decayParam;
this.value = initialValueParam;
public IirFilter(final double decay_, final double initialValue_) {
this.decay = decay_;
this.value = initialValue_;
if (decay > 1.0 || decay <= 0.0) {
throw new IllegalArgumentException("decay should be in (0.0, 1.0]");
}
}

public IirFilter(final double decayParam) {
this(decayParam, 0.0);
public IirFilter(final double decay_) {
this(decay_, 0.0);
}

public void push(final double sample) {
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/com/team766/math/IsometricTransform.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,9 @@ public class IsometricTransform {
public static final IsometricTransform IDENTITY =
new IsometricTransform(Rotation.IDENTITY, Vector3D.ZERO);

public IsometricTransform(final Rotation rotationParam, final Vector3D translationParam) {
this.rotation = rotationParam;
this.translation = translationParam;
public IsometricTransform(final Rotation rotation_, final Vector3D translation_) {
this.rotation = rotation_;
this.translation = translation_;
}

Vector3D applyInverseTo(final Vector3D u) {
Expand Down
Loading

0 comments on commit f4f525d

Please sign in to comment.