From dffa1a5cbae2741e4f173a468fd6d3a6867ffa46 Mon Sep 17 00:00:00 2001 From: Oblarg Date: Mon, 15 Jul 2019 21:22:36 -0400 Subject: [PATCH] Make null checks more descriptive (#1688) --- .../first/wpilibj/AnalogAccelerometer.java | 6 +-- .../edu/wpi/first/wpilibj/AnalogGyro.java | 8 ++-- .../first/wpilibj/AnalogTriggerOutput.java | 8 ++-- .../java/edu/wpi/first/wpilibj/Counter.java | 23 ++++++----- .../java/edu/wpi/first/wpilibj/Encoder.java | 12 +++--- .../main/java/edu/wpi/first/wpilibj/I2C.java | 8 ++-- .../java/edu/wpi/first/wpilibj/PIDBase.java | 6 +-- .../edu/wpi/first/wpilibj/Preferences.java | 6 +-- .../java/edu/wpi/first/wpilibj/Relay.java | 8 ++-- .../edu/wpi/first/wpilibj/RobotDrive.java | 34 ++++++++------- .../shuffleboard/ShuffleboardComponent.java | 9 ++-- .../shuffleboard/ShuffleboardInstance.java | 7 ++-- .../shuffleboard/ShuffleboardLayout.java | 5 ++- .../smartdashboard/SendableChooser.java | 6 +-- .../wpi/first/wpilibj/util/ErrorMessages.java | 41 +++++++++++++++++++ .../first/wpilibj/util/ErrorMessagesTest.java | 33 +++++++++++++++ 16 files changed, 148 insertions(+), 72 deletions(-) create mode 100644 wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java create mode 100644 wpilibj/src/test/java/edu/wpi/first/wpilibj/util/ErrorMessagesTest.java diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java index cd64dc82cc..abd3cdcf0a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,7 +11,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Handle operation of an analog accelerometer. The accelerometer reads acceleration directly @@ -59,7 +59,7 @@ public class AnalogAccelerometer extends SendableBase implements PIDSource { } private AnalogAccelerometer(final AnalogInput channel, final boolean allocatedChannel) { - requireNonNull(channel, "Analog Channel given was null"); + requireNonNullParam(channel, "channel", "AnalogAccelerometer"); m_allocatedChannel = allocatedChannel; m_analogChannel = channel; initAccelerometer(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java index 4283aa0ce4..259adf1b3d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,7 +12,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.interfaces.Gyro; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Use a rate gyro to return the robots heading relative to a starting position. The Gyro class @@ -69,7 +69,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { * on-board channels 0-1. */ public AnalogGyro(AnalogInput channel) { - requireNonNull(channel, "AnalogInput supplied to Gyro constructor is null"); + requireNonNullParam(channel, "channel", "AnalogGyro"); m_analog = channel; initGyro(); @@ -101,7 +101,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable { * @param offset Preset uncalibrated value to use as the gyro offset. */ public AnalogGyro(AnalogInput channel, int center, double offset) { - requireNonNull(channel, "AnalogInput supplied to Gyro constructor is null"); + requireNonNullParam(channel, "channel", "AnalogGyro"); m_analog = channel; initGyro(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java index 04971c887f..4785c2e601 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -12,7 +12,7 @@ import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Class to represent a specific output from an analog trigger. This class is used to get the @@ -68,8 +68,8 @@ public class AnalogTriggerOutput extends DigitalSource { * @param outputType An enum that specifies the output on the trigger to represent. */ public AnalogTriggerOutput(AnalogTrigger trigger, final AnalogTriggerType outputType) { - requireNonNull(trigger, "Analog Trigger given was null"); - requireNonNull(outputType, "Analog Trigger Type given was null"); + requireNonNullParam(trigger, "trigger", "AnalogTriggerOutput"); + requireNonNullParam(outputType, "outputType", "AnalogTriggerOutput"); m_trigger = trigger; m_outputType = outputType; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java index dca332a16a..73ad85238d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,6 +16,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; import static java.util.Objects.requireNonNull; /** @@ -110,7 +111,7 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { public Counter(DigitalSource source) { this(); - requireNonNull(source, "Digital Source given was null"); + requireNonNullParam(source, "source", "Counter"); setUpSource(source); } @@ -141,9 +142,9 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { boolean inverted) { this(Mode.kExternalDirection); - requireNonNull(encodingType, "Encoding type given was null"); - requireNonNull(upSource, "Up Source given was null"); - requireNonNull(downSource, "Down Source given was null"); + requireNonNullParam(encodingType, "encodingType", "Counter"); + requireNonNullParam(upSource, "upSource", "Counter"); + requireNonNullParam(downSource, "downSource", "Counter"); if (encodingType != EncodingType.k1X && encodingType != EncodingType.k2X) { throw new IllegalArgumentException("Counters only support 1X and 2X quadrature decoding!"); @@ -174,7 +175,7 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { public Counter(AnalogTrigger trigger) { this(); - requireNonNull(trigger, "The Analog Trigger given was null"); + requireNonNullParam(trigger, "trigger", "Counter"); setUpSource(trigger.createOutput(AnalogTriggerType.kState)); } @@ -237,8 +238,8 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { * @param triggerType The analog trigger output that will trigger the counter. */ public void setUpSource(AnalogTrigger analogTrigger, AnalogTriggerType triggerType) { - requireNonNull(analogTrigger, "Analog Trigger given was null"); - requireNonNull(triggerType, "Analog Trigger Type given was null"); + requireNonNullParam(analogTrigger, "analogTrigger", "setUpSource"); + requireNonNullParam(triggerType, "triggerType", "setUpSource"); setUpSource(analogTrigger.createOutput(triggerType)); m_allocatedUpSource = true; @@ -307,8 +308,8 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { * @param triggerType The analog trigger output that will trigger the counter. */ public void setDownSource(AnalogTrigger analogTrigger, AnalogTriggerType triggerType) { - requireNonNull(analogTrigger, "Analog Trigger given was null"); - requireNonNull(triggerType, "Analog Trigger Type given was null"); + requireNonNullParam(analogTrigger, "analogTrigger", "setDownSource"); + requireNonNullParam(triggerType, "analogTrigger", "setDownSource"); setDownSource(analogTrigger.createOutput(triggerType)); m_allocatedDownSource = true; @@ -530,7 +531,7 @@ public class Counter extends SendableBase implements CounterBase, PIDSource { */ @Override public void setPIDSourceType(PIDSourceType pidSource) { - requireNonNull(pidSource, "PID Source Parameter given was null"); + requireNonNullParam(pidSource, "pidSource", "setPIDSourceType"); if (pidSource != PIDSourceType.kDisplacement && pidSource != PIDSourceType.kRate) { throw new IllegalArgumentException("PID Source parameter was not valid type: " + pidSource); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java index 594fe0a135..6425e0dfcf 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -13,7 +13,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.AllocationException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Class to read quadrature encoders. @@ -126,7 +126,7 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { */ public Encoder(final int channelA, final int channelB, boolean reverseDirection, final EncodingType encodingType) { - requireNonNull(encodingType, "Given encoding type was null"); + requireNonNullParam(encodingType, "encodingType", "Encoder"); m_allocatedA = true; m_allocatedB = true; @@ -223,9 +223,9 @@ public class Encoder extends SendableBase implements CounterBase, PIDSource { */ public Encoder(DigitalSource sourceA, DigitalSource sourceB, boolean reverseDirection, final EncodingType encodingType) { - requireNonNull(sourceA, "Digital Source A was null"); - requireNonNull(sourceB, "Digital Source B was null"); - requireNonNull(encodingType, "Given encoding type was null"); + requireNonNullParam(sourceA, "sourceA", "Encoder"); + requireNonNullParam(sourceB, "sourceB", "Encoder"); + requireNonNullParam(encodingType, "encodingType", "Encoder"); m_allocatedA = false; m_allocatedB = false; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java index 67a171c55c..a408e47396 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -14,7 +14,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.I2CJNI; import edu.wpi.first.hal.util.BoundaryException; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * I2C bus interface class. @@ -219,7 +219,7 @@ public class I2C implements AutoCloseable { * @return Transfer Aborted... false for success, true for aborted. */ public boolean read(int registerAddress, int count, byte[] buffer) { - requireNonNull(buffer, "Null return buffer was given"); + requireNonNullParam(buffer, "buffer", "read"); if (count < 1) { throw new BoundaryException("Value must be at least 1, " + count + " given"); @@ -284,7 +284,7 @@ public class I2C implements AutoCloseable { * @return Transfer Aborted... false for success, true for aborted. */ public boolean readOnly(byte[] buffer, int count) { - requireNonNull(buffer, "Null return buffer was given"); + requireNonNullParam(buffer, "buffer", "readOnly"); if (count < 1) { throw new BoundaryException("Value must be at least 1, " + count + " given"); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java index 6842387473..974d5c40b5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java @@ -14,7 +14,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.BoundaryException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Class implements a PID Control Loop. @@ -155,8 +155,8 @@ public class PIDBase extends SendableBase implements PIDInterface, PIDOutput { public PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) { super(false); - requireNonNull(source, "Null PIDSource was given"); - requireNonNull(output, "Null PIDOutput was given"); + requireNonNullParam(source, "PIDSource", "PIDBase"); + requireNonNullParam(output, "output", "PIDBase"); m_setpointTimer = new Timer(); m_setpointTimer.start(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java index 45d9e0e1f1..ebc2a1934b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,7 +16,7 @@ import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.networktables.NetworkTableInstance; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * The preferences class provides a relatively simple way to save important values to the roboRIO to @@ -88,7 +88,7 @@ public final class Preferences { * @throws NullPointerException if value is null */ public void putString(String key, String value) { - requireNonNull(value, "Provided value was null"); + requireNonNullParam(value, "value", "putString"); NetworkTableEntry entry = m_table.getEntry(key); entry.setString(value); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java index 549a6814bd..94a980a42f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -16,7 +16,7 @@ import edu.wpi.first.hal.RelayJNI; import edu.wpi.first.hal.util.UncleanStatusException; import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Class for VEX Robotics Spike style relay outputs. Relays are intended to be connected to Spikes @@ -128,7 +128,7 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { m_sendableImpl = new SendableImpl(true); m_channel = channel; - m_direction = requireNonNull(direction, "Null Direction was given"); + m_direction = requireNonNullParam(direction, "direction", "Relay"); initRelay(); set(Value.kOff); } @@ -347,7 +347,7 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { * @param direction The direction for the relay to operate in */ public void setDirection(Direction direction) { - requireNonNull(direction, "Null Direction was given"); + requireNonNullParam(direction, "direction", "setDirection"); if (m_direction == direction) { return; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java index 6f020fdab3..297dd37312 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -11,7 +11,7 @@ import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; -import static java.util.Objects.requireNonNull; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; /** * Utility class for handling Robot drive based on a definition of the motor configuration. The @@ -111,8 +111,8 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { * @param rightMotor the right SpeedController object used to drive the robot. */ public RobotDrive(SpeedController leftMotor, SpeedController rightMotor) { - requireNonNull(leftMotor, "Provided left motor was null"); - requireNonNull(rightMotor, "Provided right motor was null"); + requireNonNullParam(leftMotor, "leftMotor", "RobotDrive"); + requireNonNullParam(rightMotor, "rightMotor", "RobotDrive"); m_frontLeftMotor = null; m_rearLeftMotor = leftMotor; @@ -136,10 +136,10 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { */ public RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor, SpeedController frontRightMotor, SpeedController rearRightMotor) { - m_frontLeftMotor = requireNonNull(frontLeftMotor, "frontLeftMotor cannot be null"); - m_rearLeftMotor = requireNonNull(rearLeftMotor, "rearLeftMotor cannot be null"); - m_frontRightMotor = requireNonNull(frontRightMotor, "frontRightMotor cannot be null"); - m_rearRightMotor = requireNonNull(rearRightMotor, "rearRightMotor cannot be null"); + m_frontLeftMotor = requireNonNullParam(frontLeftMotor, "frontLeftMotor", "RobotDrive"); + m_rearLeftMotor = requireNonNullParam(rearLeftMotor, "rearLeftMotor", "RobotDrive"); + m_frontRightMotor = requireNonNullParam(frontRightMotor, "frontRightMotor", "RobotDrive"); + m_rearRightMotor = requireNonNullParam(rearRightMotor, "rearRightMotor", "RobotDrive"); m_sensitivity = kDefaultSensitivity; m_maxOutput = kDefaultMaxOutput; m_allocatedSpeedControllers = false; @@ -206,8 +206,8 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { * @param rightStick The joystick to control the right side of the robot. */ public void tankDrive(GenericHID leftStick, GenericHID rightStick) { - requireNonNull(leftStick, "Provided left stick was null"); - requireNonNull(rightStick, "Provided right stick was null"); + requireNonNullParam(leftStick, "leftStick", "tankDrive"); + requireNonNullParam(rightStick, "rightStick", "tankDrive"); tankDrive(leftStick.getY(), rightStick.getY(), true); } @@ -221,8 +221,8 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds */ public void tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs) { - requireNonNull(leftStick, "Provided left stick was null"); - requireNonNull(rightStick, "Provided right stick was null"); + requireNonNullParam(leftStick, "leftStick", "tankDrive"); + requireNonNullParam(rightStick, "rightStick", "tankDrive"); tankDrive(leftStick.getY(), rightStick.getY(), squaredInputs); } @@ -239,8 +239,8 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { */ public void tankDrive(GenericHID leftStick, final int leftAxis, GenericHID rightStick, final int rightAxis) { - requireNonNull(leftStick, "Provided left stick was null"); - requireNonNull(rightStick, "Provided right stick was null"); + requireNonNullParam(leftStick, "leftStick", "tankDrive"); + requireNonNullParam(rightStick, "rightStick", "tankDrive"); tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), true); } @@ -257,8 +257,8 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { */ public void tankDrive(GenericHID leftStick, final int leftAxis, GenericHID rightStick, final int rightAxis, boolean squaredInputs) { - requireNonNull(leftStick, "Provided left stick was null"); - requireNonNull(rightStick, "Provided right stick was null"); + requireNonNullParam(leftStick, "leftStick", "tankDrive"); + requireNonNullParam(rightStick, "rightStick", "tankDrive"); tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), squaredInputs); } @@ -547,8 +547,6 @@ public class RobotDrive extends MotorSafety implements AutoCloseable { * @param rightOutput The speed to send to the right side of the robot. */ public void setLeftRightMotorOutputs(double leftOutput, double rightOutput) { - requireNonNull(m_rearLeftMotor, "Provided left motor was null"); - requireNonNull(m_rearRightMotor, "Provided right motor was null"); if (m_frontLeftMotor != null) { m_frontLeftMotor.set(limit(leftOutput) * m_maxOutput); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java index ba87d826c3..5d903961b7 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) 2018 FIRST. All Rights Reserved. */ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ @@ -8,10 +8,11 @@ package edu.wpi.first.wpilibj.shuffleboard; import java.util.Map; -import java.util.Objects; import edu.wpi.first.networktables.NetworkTable; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; + /** * A generic component in Shuffleboard. * @@ -30,8 +31,8 @@ public abstract class ShuffleboardComponent> private int m_height = -1; protected ShuffleboardComponent(ShuffleboardContainer parent, String title, String type) { - m_parent = Objects.requireNonNull(parent, "Parent cannot be null"); - m_title = Objects.requireNonNull(title, "Title cannot be null"); + m_parent = requireNonNullParam(parent, "parent", "ShuffleboardComponent"); + m_title = requireNonNullParam(title, "title", "ShuffleboardComponent"); m_type = type; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java index 3a5dd16365..8af1d787ed 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java @@ -9,7 +9,6 @@ package edu.wpi.first.wpilibj.shuffleboard; import java.util.LinkedHashMap; import java.util.Map; -import java.util.Objects; import java.util.function.Consumer; import edu.wpi.first.hal.FRCNetComm.tResourceType; @@ -18,6 +17,8 @@ import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEntry; import edu.wpi.first.networktables.NetworkTableInstance; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; + final class ShuffleboardInstance implements ShuffleboardRoot { private final Map m_tabs = new LinkedHashMap<>(); @@ -32,7 +33,7 @@ final class ShuffleboardInstance implements ShuffleboardRoot { * @param ntInstance the NetworkTables instance to use */ ShuffleboardInstance(NetworkTableInstance ntInstance) { - Objects.requireNonNull(ntInstance, "NetworkTable instance cannot be null"); + requireNonNullParam(ntInstance, "ntInstance", "ShuffleboardInstance"); m_rootTable = ntInstance.getTable(Shuffleboard.kBaseTableName); m_rootMetaTable = m_rootTable.getSubTable(".metadata"); m_selectedTabEntry = m_rootMetaTable.getEntry("Selected"); @@ -41,7 +42,7 @@ final class ShuffleboardInstance implements ShuffleboardRoot { @Override public ShuffleboardTab getTab(String title) { - Objects.requireNonNull(title, "Tab title cannot be null"); + requireNonNullParam(title, "title", "getTab"); if (!m_tabs.containsKey(title)) { m_tabs.put(title, new ShuffleboardTab(this, title)); m_tabsChanged = true; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java index dbb621636a..8f3014a3ee 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java @@ -9,7 +9,6 @@ package edu.wpi.first.wpilibj.shuffleboard; import java.util.List; import java.util.NoSuchElementException; -import java.util.Objects; import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; import java.util.function.Supplier; @@ -17,6 +16,8 @@ import java.util.function.Supplier; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.wpilibj.Sendable; +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; + /** * A layout in a Shuffleboard tab. Layouts can contain widgets and other layouts. */ @@ -26,7 +27,7 @@ public class ShuffleboardLayout extends ShuffleboardComponent extends SendableBase { * @param object the option */ public void setDefaultOption(String name, V object) { - requireNonNull(name, "Provided name was null"); + requireNonNullParam(name, "name", "setDefaultOption"); m_defaultChoice = name; addOption(name, object); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java new file mode 100644 index 0000000000..8bc86b25d3 --- /dev/null +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/ErrorMessages.java @@ -0,0 +1,41 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.wpilibj.util; + +import static java.util.Objects.requireNonNull; + +/** + * Utility class for common WPILib error messages. + */ +public final class ErrorMessages { + /** + * Utility class, so constructor is private. + */ + private ErrorMessages() { + throw new UnsupportedOperationException("This is a utility class!"); + } + + /** + * Requires that a parameter of a method not be null; prints an error message with + * helpful debugging instructions if the parameter is null. + * + * @param obj The parameter that must not be null. + * @param paramName The name of the parameter. + * @param methodName The name of the method. + */ + public static T requireNonNullParam(T obj, String paramName, String methodName) { + return requireNonNull(obj, + "Parameter " + paramName + " in method " + methodName + " was null when it" + + " should not have been! Check the stacktrace to find the responsible line of code - " + + "usually, it is the first line of user-written code indicated in the stacktrace. " + + "Make sure all objects passed to the method in question were properly initialized -" + + " note that this may not be obvious if it is being called under " + + "dynamically-changing conditions! Please do not seek additional technical assistance" + + " without doing this first!"); + } +} diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/util/ErrorMessagesTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/util/ErrorMessagesTest.java new file mode 100644 index 0000000000..17c733375b --- /dev/null +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/util/ErrorMessagesTest.java @@ -0,0 +1,33 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package edu.wpi.first.wpilibj.util; + +import org.junit.jupiter.api.Test; + +import edu.wpi.first.wpilibj.UtilityClassTest; + +import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; +import static org.junit.jupiter.api.Assertions.assertDoesNotThrow; +import static org.junit.jupiter.api.Assertions.assertThrows; + +class ErrorMessagesTest extends UtilityClassTest { + ErrorMessagesTest() { + super(ErrorMessages.class); + } + + @Test + void requireNonNullParamNullTest() { + assertThrows(NullPointerException.class, () -> requireNonNullParam(null, "testParam", + "testMethod")); + } + + @Test + void requireNonNullParamNotNullTest() { + assertDoesNotThrow(() -> requireNonNullParam("null", "testParam", "testMethod")); + } +}