From 0421ffc3f8bfdd0086288c18d60b5f9eae1cfeed Mon Sep 17 00:00:00 2001 From: braykoff <99614905+Braykoff@users.noreply.github.com> Date: Tue, 22 Oct 2024 23:12:47 -0400 Subject: [PATCH 1/4] Java implementation --- .../wpi/first/wpilibj/RobotController.java | 128 ++++++++++++++++++ 1 file changed, 128 insertions(+) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java index dc56bbb3624..b6cac878560 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java @@ -4,12 +4,21 @@ package edu.wpi.first.wpilibj; +import static edu.wpi.first.units.Units.Amps; +import static edu.wpi.first.units.Units.Celsius; +import static edu.wpi.first.units.Units.Microseconds; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.HALUtil; import edu.wpi.first.hal.LEDJNI; import edu.wpi.first.hal.PowerJNI; import edu.wpi.first.hal.can.CANJNI; import edu.wpi.first.hal.can.CANStatus; +import edu.wpi.first.units.measure.Current; +import edu.wpi.first.units.measure.Temperature; +import edu.wpi.first.units.measure.Time; +import edu.wpi.first.units.measure.Voltage; /** Contains functions for roboRIO functionality. */ public final class RobotController { @@ -76,6 +85,15 @@ public static long getFPGATime() { return HALUtil.getFPGATime(); } + /** + * Read the microsecond timer in a measure from the FPGA. + * + * @return The current time according to the FPGA in a measure. + */ + public static Time getMeasureFPGATime() { + return Microseconds.of(HALUtil.getFPGATime()); + } + /** * Get the state of the "USER" button on the roboRIO. * @@ -98,6 +116,15 @@ public static double getBatteryVoltage() { return PowerJNI.getVinVoltage(); } + /** + * Read the battery voltage in a measure. + * + * @return The battery voltage in a measure. + */ + public static Voltage getMeasureBatteryVoltage() { + return Volts.of(PowerJNI.getVinVoltage()); + } + /** * Gets a value indicating whether the FPGA outputs are enabled. The outputs may be disabled if * the robot is disabled or e-stopped, the watchdog has expired, or if the roboRIO browns out. @@ -154,6 +181,15 @@ public static double getInputVoltage() { return PowerJNI.getVinVoltage(); } + /** + * Get the input voltage to the robot controller in a measure. + * + * @return The controller input voltage value in a measure. + */ + public static Voltage getMeasureInputVoltage() { + return Volts.of(PowerJNI.getVinVoltage()); + } + /** * Get the input current to the robot controller. * @@ -163,6 +199,15 @@ public static double getInputCurrent() { return PowerJNI.getVinCurrent(); } + /** + * Get the input current to the robot controller in a measure. + * + * @return The controller input current value in a measure. + */ + public static final Current getMeasureInputCurrent() { + return Amps.of(PowerJNI.getVinCurrent()); + } + /** * Get the voltage of the 3.3V rail. * @@ -172,6 +217,15 @@ public static double getVoltage3V3() { return PowerJNI.getUserVoltage3V3(); } + /** + * Get the voltage in a measure of the 3.3V rail. + * + * @return The controller 3.3V rail voltage value in a measure. + */ + public static final Voltage getMeasureVoltage3V3() { + return Volts.of(PowerJNI.getUserVoltage3V3()); + } + /** * Get the current output of the 3.3V rail. * @@ -181,6 +235,15 @@ public static double getCurrent3V3() { return PowerJNI.getUserCurrent3V3(); } + /** + * Get the current output in a measure of the 3.3V rail. + * + * @return The controller 3.3V rail output current value in a measure. + */ + public static Current getMeasureCurrent3V3() { + return Amps.of(PowerJNI.getUserCurrent3V3()); + } + /** * Enables or disables the 3.3V rail. * @@ -218,6 +281,15 @@ public static double getVoltage5V() { return PowerJNI.getUserVoltage5V(); } + /** + * Get the voltage in a measure of the 5V rail. + * + * @return The controller 5V rail voltage value in a measure. + */ + public static Voltage getMeasureVoltage5V() { + return Volts.of(PowerJNI.getUserVoltage5V()); + } + /** * Get the current output of the 5V rail. * @@ -227,6 +299,15 @@ public static double getCurrent5V() { return PowerJNI.getUserCurrent5V(); } + /** + * Get the current output in a measure of the 5V rail. + * + * @return The controller 5V rail output current value in a measure. + */ + public static Current getMeasureCurrent5V() { + return Amps.of(PowerJNI.getUserCurrent5V()); + } + /** * Enables or disables the 5V rail. * @@ -264,6 +345,15 @@ public static double getVoltage6V() { return PowerJNI.getUserVoltage6V(); } + /** + * Get the voltage in a measure of the 6V rail. + * + * @return The controller 6V rail voltage value in a measure. + */ + public static Voltage getMeasureVoltage6V() { + return Volts.of(PowerJNI.getUserVoltage6V()); + } + /** * Get the current output of the 6V rail. * @@ -273,6 +363,15 @@ public static double getCurrent6V() { return PowerJNI.getUserCurrent6V(); } + /** + * Get the current output in a measure of the 6V rail. + * + * @return The controller 6V rail output current value in a measure. + */ + public static Current getMeasureCurrent6V() { + return Amps.of(PowerJNI.getUserCurrent6V()); + } + /** * Enables or disables the 6V rail. * @@ -315,6 +414,15 @@ public static double getBrownoutVoltage() { return PowerJNI.getBrownoutVoltage(); } + /** + * Get the current brownout voltage setting in a measure. + * + * @return The brownout voltage in a measure. + */ + public static Voltage getMeasureBrownoutVoltage() { + return Volts.of(PowerJNI.getBrownoutVoltage()); + } + /** * Set the voltage the roboRIO will brownout and disable all outputs. * @@ -326,6 +434,17 @@ public static void setBrownoutVoltage(double brownoutVoltage) { PowerJNI.setBrownoutVoltage(brownoutVoltage); } + /** + * Set the voltage in a measure the roboRIO will brownout and disable all outputs. + * + *
Note that this only does anything on the roboRIO 2. On the roboRIO it is a no-op. + * + * @param brownoutVoltage The brownout voltage in a measure + */ + public static void setBrownoutVoltage(Voltage brownoutVoltage) { + PowerJNI.setBrownoutVoltage(brownoutVoltage.baseUnitMagnitude()); + } + /** * Get the current CPU temperature in degrees Celsius. * @@ -335,6 +454,15 @@ public static double getCPUTemp() { return PowerJNI.getCPUTemp(); } + /** + * Get the current CPU temperature in a measure. + * + * @return current CPU temperature in a measure. + */ + public static Temperature getMeasureCPUTemp() { + return Celsius.of(PowerJNI.getCPUTemp()); + } + /** State for the radio led. */ public enum RadioLEDState { /** Off. */ From c13b870a54149d0c4ce8200c28317eb54f2a4a2f Mon Sep 17 00:00:00 2001 From: braykoff <99614905+Braykoff@users.noreply.github.com> Date: Tue, 22 Oct 2024 23:26:23 -0400 Subject: [PATCH 2/4] linted --- .../src/main/java/edu/wpi/first/wpilibj/RobotController.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java index b6cac878560..5e9d88d066d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java @@ -204,7 +204,7 @@ public static double getInputCurrent() { * * @return The controller input current value in a measure. */ - public static final Current getMeasureInputCurrent() { + public static Current getMeasureInputCurrent() { return Amps.of(PowerJNI.getVinCurrent()); } @@ -222,7 +222,7 @@ public static double getVoltage3V3() { * * @return The controller 3.3V rail voltage value in a measure. */ - public static final Voltage getMeasureVoltage3V3() { + public static Voltage getMeasureVoltage3V3() { return Volts.of(PowerJNI.getUserVoltage3V3()); } From ac2b6cddd392d87e83a0bbe67df87b539c67a47e Mon Sep 17 00:00:00 2001 From: braykoff <99614905+Braykoff@users.noreply.github.com> Date: Thu, 24 Oct 2024 14:54:34 -0400 Subject: [PATCH 3/4] Switched to MutMeasures --- .../wpi/first/wpilibj/RobotController.java | 129 +++++++++++------- 1 file changed, 78 insertions(+), 51 deletions(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java index 5e9d88d066d..c4224b25d8f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java @@ -15,13 +15,28 @@ import edu.wpi.first.hal.PowerJNI; import edu.wpi.first.hal.can.CANJNI; import edu.wpi.first.hal.can.CANStatus; -import edu.wpi.first.units.measure.Current; -import edu.wpi.first.units.measure.Temperature; -import edu.wpi.first.units.measure.Time; +import edu.wpi.first.units.measure.MutCurrent; +import edu.wpi.first.units.measure.MutTemperature; +import edu.wpi.first.units.measure.MutTime; +import edu.wpi.first.units.measure.MutVoltage; import edu.wpi.first.units.measure.Voltage; /** Contains functions for roboRIO functionality. */ public final class RobotController { + // Mutable measures + private static final MutTime m_mutFPGATime = Microseconds.mutable(0.0); + private static final MutVoltage m_mutBatteryVoltage = Volts.mutable(0.0); + private static final MutVoltage m_mutInputVoltage = Volts.mutable(0.0); + private static final MutCurrent m_mutInputCurrent = Amps.mutable(0.0); + private static final MutVoltage m_mutVoltage3V3 = Volts.mutable(0.0); + private static final MutCurrent m_mutCurrent3V3 = Amps.mutable(0.0); + private static final MutVoltage m_mutVoltage5V = Volts.mutable(0.0); + private static final MutCurrent m_mutCurrent5V = Amps.mutable(0.0); + private static final MutVoltage m_mutVoltage6V = Volts.mutable(0.0); + private static final MutCurrent m_mutCurrent6V = Amps.mutable(0.0); + private static final MutVoltage m_mutBrownoutVoltage = Volts.mutable(0.0); + private static final MutTemperature m_mutCPUTemp = Celsius.mutable(0.0); + private RobotController() { throw new UnsupportedOperationException("This is a utility class!"); } @@ -86,12 +101,13 @@ public static long getFPGATime() { } /** - * Read the microsecond timer in a measure from the FPGA. + * Read the microsecond timer in a mutable measure from the FPGA. * - * @return The current time according to the FPGA in a measure. + * @return The current time according to the FPGA in a mutable measure. */ - public static Time getMeasureFPGATime() { - return Microseconds.of(HALUtil.getFPGATime()); + public static MutTime getMeasureFPGATime() { + m_mutFPGATime.mut_replace(HALUtil.getFPGATime(), Microseconds); + return m_mutFPGATime; } /** @@ -117,12 +133,13 @@ public static double getBatteryVoltage() { } /** - * Read the battery voltage in a measure. + * Read the battery voltage in a mutable measure. * - * @return The battery voltage in a measure. + * @return The battery voltage in a mutable measure. */ - public static Voltage getMeasureBatteryVoltage() { - return Volts.of(PowerJNI.getVinVoltage()); + public static MutVoltage getMeasureBatteryVoltage() { + m_mutBatteryVoltage.mut_replace(PowerJNI.getVinVoltage(), Volts); + return m_mutBatteryVoltage; } /** @@ -182,12 +199,13 @@ public static double getInputVoltage() { } /** - * Get the input voltage to the robot controller in a measure. + * Get the input voltage to the robot controller in a mutable measure. * - * @return The controller input voltage value in a measure. + * @return The controller input voltage value in a mutable measure. */ - public static Voltage getMeasureInputVoltage() { - return Volts.of(PowerJNI.getVinVoltage()); + public static MutVoltage getMeasureInputVoltage() { + m_mutInputVoltage.mut_replace(PowerJNI.getVinVoltage(), Volts); + return m_mutInputVoltage; } /** @@ -200,12 +218,13 @@ public static double getInputCurrent() { } /** - * Get the input current to the robot controller in a measure. + * Get the input current to the robot controller in a mutable measure. * - * @return The controller input current value in a measure. + * @return The controller input current value in a mutable measure. */ - public static Current getMeasureInputCurrent() { - return Amps.of(PowerJNI.getVinCurrent()); + public static MutCurrent getMeasureInputCurrent() { + m_mutInputCurrent.mut_replace(PowerJNI.getVinCurrent(), Amps); + return m_mutInputCurrent; } /** @@ -218,12 +237,13 @@ public static double getVoltage3V3() { } /** - * Get the voltage in a measure of the 3.3V rail. + * Get the voltage in a mutable measure of the 3.3V rail. * - * @return The controller 3.3V rail voltage value in a measure. + * @return The controller 3.3V rail voltage value in a mutable measure. */ - public static Voltage getMeasureVoltage3V3() { - return Volts.of(PowerJNI.getUserVoltage3V3()); + public static MutVoltage getMeasureVoltage3V3() { + m_mutVoltage3V3.mut_replace(PowerJNI.getUserVoltage3V3(), Volts); + return m_mutVoltage3V3; } /** @@ -236,12 +256,13 @@ public static double getCurrent3V3() { } /** - * Get the current output in a measure of the 3.3V rail. + * Get the current output in a mutable measure of the 3.3V rail. * - * @return The controller 3.3V rail output current value in a measure. + * @return The controller 3.3V rail output current value in a mutable measure. */ - public static Current getMeasureCurrent3V3() { - return Amps.of(PowerJNI.getUserCurrent3V3()); + public static MutCurrent getMeasureCurrent3V3() { + m_mutCurrent3V3.mut_replace(PowerJNI.getUserCurrent3V3(), Amps); + return m_mutCurrent3V3; } /** @@ -282,12 +303,13 @@ public static double getVoltage5V() { } /** - * Get the voltage in a measure of the 5V rail. + * Get the voltage in a mutable measure of the 5V rail. * - * @return The controller 5V rail voltage value in a measure. + * @return The controller 5V rail voltage value in a mutable measure. */ - public static Voltage getMeasureVoltage5V() { - return Volts.of(PowerJNI.getUserVoltage5V()); + public static MutVoltage getMeasureVoltage5V() { + m_mutVoltage5V.mut_replace(PowerJNI.getUserVoltage5V(), Volts); + return m_mutVoltage5V; } /** @@ -300,12 +322,13 @@ public static double getCurrent5V() { } /** - * Get the current output in a measure of the 5V rail. + * Get the current output in a mutable measure of the 5V rail. * - * @return The controller 5V rail output current value in a measure. + * @return The controller 5V rail output current value in a mutable measure. */ - public static Current getMeasureCurrent5V() { - return Amps.of(PowerJNI.getUserCurrent5V()); + public static MutCurrent getMeasureCurrent5V() { + m_mutCurrent5V.mut_replace(PowerJNI.getUserCurrent5V(), Amps); + return m_mutCurrent5V; } /** @@ -346,12 +369,13 @@ public static double getVoltage6V() { } /** - * Get the voltage in a measure of the 6V rail. + * Get the voltage in a mutable measure of the 6V rail. * - * @return The controller 6V rail voltage value in a measure. + * @return The controller 6V rail voltage value in a mutable measure. */ - public static Voltage getMeasureVoltage6V() { - return Volts.of(PowerJNI.getUserVoltage6V()); + public static MutVoltage getMeasureVoltage6V() { + m_mutVoltage6V.mut_replace(PowerJNI.getUserVoltage6V(), Volts); + return m_mutVoltage6V; } /** @@ -364,12 +388,13 @@ public static double getCurrent6V() { } /** - * Get the current output in a measure of the 6V rail. + * Get the current output in a mutable measure of the 6V rail. * - * @return The controller 6V rail output current value in a measure. + * @return The controller 6V rail output current value in a mutable measure. */ - public static Current getMeasureCurrent6V() { - return Amps.of(PowerJNI.getUserCurrent6V()); + public static MutCurrent getMeasureCurrent6V() { + m_mutCurrent6V.mut_replace(PowerJNI.getUserCurrent6V(), Amps); + return m_mutCurrent6V; } /** @@ -415,12 +440,13 @@ public static double getBrownoutVoltage() { } /** - * Get the current brownout voltage setting in a measure. + * Get the current brownout voltage setting in a mutable measure. * - * @return The brownout voltage in a measure. + * @return The brownout voltage in a mutable measure. */ - public static Voltage getMeasureBrownoutVoltage() { - return Volts.of(PowerJNI.getBrownoutVoltage()); + public static MutVoltage getMeasureBrownoutVoltage() { + m_mutBrownoutVoltage.mut_replace(PowerJNI.getBrownoutVoltage(), Volts); + return m_mutBrownoutVoltage; } /** @@ -455,12 +481,13 @@ public static double getCPUTemp() { } /** - * Get the current CPU temperature in a measure. + * Get the current CPU temperature in a mutable measure. * - * @return current CPU temperature in a measure. + * @return current CPU temperature in a mutable measure. */ - public static Temperature getMeasureCPUTemp() { - return Celsius.of(PowerJNI.getCPUTemp()); + public static MutTemperature getMeasureCPUTemp() { + m_mutCPUTemp.mut_replace(PowerJNI.getCPUTemp(), Celsius); + return m_mutCPUTemp; } /** State for the radio led. */ From 136501ac3c5d623e31353e7c64d527d92bb9d31e Mon Sep 17 00:00:00 2001 From: braykoff <99614905+Braykoff@users.noreply.github.com> Date: Sat, 26 Oct 2024 15:01:23 -0400 Subject: [PATCH 4/4] Switched return type --- .../wpi/first/wpilibj/RobotController.java | 75 ++++++++++--------- 1 file changed, 39 insertions(+), 36 deletions(-) diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java index c4224b25d8f..44b15609512 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java @@ -15,10 +15,13 @@ import edu.wpi.first.hal.PowerJNI; import edu.wpi.first.hal.can.CANJNI; import edu.wpi.first.hal.can.CANStatus; +import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.MutCurrent; import edu.wpi.first.units.measure.MutTemperature; import edu.wpi.first.units.measure.MutTime; import edu.wpi.first.units.measure.MutVoltage; +import edu.wpi.first.units.measure.Temperature; +import edu.wpi.first.units.measure.Time; import edu.wpi.first.units.measure.Voltage; /** Contains functions for roboRIO functionality. */ @@ -101,11 +104,11 @@ public static long getFPGATime() { } /** - * Read the microsecond timer in a mutable measure from the FPGA. + * Read the microsecond timer in a measure from the FPGA. * - * @return The current time according to the FPGA in a mutable measure. + * @return The current time according to the FPGA in a measure. */ - public static MutTime getMeasureFPGATime() { + public static Time getMeasureFPGATime() { m_mutFPGATime.mut_replace(HALUtil.getFPGATime(), Microseconds); return m_mutFPGATime; } @@ -133,11 +136,11 @@ public static double getBatteryVoltage() { } /** - * Read the battery voltage in a mutable measure. + * Read the battery voltage in a measure. * - * @return The battery voltage in a mutable measure. + * @return The battery voltage in a measure. */ - public static MutVoltage getMeasureBatteryVoltage() { + public static Voltage getMeasureBatteryVoltage() { m_mutBatteryVoltage.mut_replace(PowerJNI.getVinVoltage(), Volts); return m_mutBatteryVoltage; } @@ -199,11 +202,11 @@ public static double getInputVoltage() { } /** - * Get the input voltage to the robot controller in a mutable measure. + * Get the input voltage to the robot controller in a measure. * - * @return The controller input voltage value in a mutable measure. + * @return The controller input voltage value in a measure. */ - public static MutVoltage getMeasureInputVoltage() { + public static Voltage getMeasureInputVoltage() { m_mutInputVoltage.mut_replace(PowerJNI.getVinVoltage(), Volts); return m_mutInputVoltage; } @@ -218,11 +221,11 @@ public static double getInputCurrent() { } /** - * Get the input current to the robot controller in a mutable measure. + * Get the input current to the robot controller in a measure. * - * @return The controller input current value in a mutable measure. + * @return The controller input current value in a measure. */ - public static MutCurrent getMeasureInputCurrent() { + public static Current getMeasureInputCurrent() { m_mutInputCurrent.mut_replace(PowerJNI.getVinCurrent(), Amps); return m_mutInputCurrent; } @@ -237,11 +240,11 @@ public static double getVoltage3V3() { } /** - * Get the voltage in a mutable measure of the 3.3V rail. + * Get the voltage in a measure of the 3.3V rail. * - * @return The controller 3.3V rail voltage value in a mutable measure. + * @return The controller 3.3V rail voltage value in a measure. */ - public static MutVoltage getMeasureVoltage3V3() { + public static Voltage getMeasureVoltage3V3() { m_mutVoltage3V3.mut_replace(PowerJNI.getUserVoltage3V3(), Volts); return m_mutVoltage3V3; } @@ -256,11 +259,11 @@ public static double getCurrent3V3() { } /** - * Get the current output in a mutable measure of the 3.3V rail. + * Get the current output in a measure of the 3.3V rail. * - * @return The controller 3.3V rail output current value in a mutable measure. + * @return The controller 3.3V rail output current value in a measure. */ - public static MutCurrent getMeasureCurrent3V3() { + public static Current getMeasureCurrent3V3() { m_mutCurrent3V3.mut_replace(PowerJNI.getUserCurrent3V3(), Amps); return m_mutCurrent3V3; } @@ -303,11 +306,11 @@ public static double getVoltage5V() { } /** - * Get the voltage in a mutable measure of the 5V rail. + * Get the voltage in a measure of the 5V rail. * - * @return The controller 5V rail voltage value in a mutable measure. + * @return The controller 5V rail voltage value in a measure. */ - public static MutVoltage getMeasureVoltage5V() { + public static Voltage getMeasureVoltage5V() { m_mutVoltage5V.mut_replace(PowerJNI.getUserVoltage5V(), Volts); return m_mutVoltage5V; } @@ -322,11 +325,11 @@ public static double getCurrent5V() { } /** - * Get the current output in a mutable measure of the 5V rail. + * Get the current output in a measure of the 5V rail. * - * @return The controller 5V rail output current value in a mutable measure. + * @return The controller 5V rail output current value in a measure. */ - public static MutCurrent getMeasureCurrent5V() { + public static Current getMeasureCurrent5V() { m_mutCurrent5V.mut_replace(PowerJNI.getUserCurrent5V(), Amps); return m_mutCurrent5V; } @@ -369,11 +372,11 @@ public static double getVoltage6V() { } /** - * Get the voltage in a mutable measure of the 6V rail. + * Get the voltage in a measure of the 6V rail. * - * @return The controller 6V rail voltage value in a mutable measure. + * @return The controller 6V rail voltage value in a measure. */ - public static MutVoltage getMeasureVoltage6V() { + public static Voltage getMeasureVoltage6V() { m_mutVoltage6V.mut_replace(PowerJNI.getUserVoltage6V(), Volts); return m_mutVoltage6V; } @@ -388,11 +391,11 @@ public static double getCurrent6V() { } /** - * Get the current output in a mutable measure of the 6V rail. + * Get the current output in a measure of the 6V rail. * - * @return The controller 6V rail output current value in a mutable measure. + * @return The controller 6V rail output current value in a measure. */ - public static MutCurrent getMeasureCurrent6V() { + public static Current getMeasureCurrent6V() { m_mutCurrent6V.mut_replace(PowerJNI.getUserCurrent6V(), Amps); return m_mutCurrent6V; } @@ -440,11 +443,11 @@ public static double getBrownoutVoltage() { } /** - * Get the current brownout voltage setting in a mutable measure. + * Get the current brownout voltage setting in a measure. * - * @return The brownout voltage in a mutable measure. + * @return The brownout voltage in a measure. */ - public static MutVoltage getMeasureBrownoutVoltage() { + public static Voltage getMeasureBrownoutVoltage() { m_mutBrownoutVoltage.mut_replace(PowerJNI.getBrownoutVoltage(), Volts); return m_mutBrownoutVoltage; } @@ -481,11 +484,11 @@ public static double getCPUTemp() { } /** - * Get the current CPU temperature in a mutable measure. + * Get the current CPU temperature in a measure. * - * @return current CPU temperature in a mutable measure. + * @return current CPU temperature in a measure. */ - public static MutTemperature getMeasureCPUTemp() { + public static Temperature getMeasureCPUTemp() { m_mutCPUTemp.mut_replace(PowerJNI.getCPUTemp(), Celsius); return m_mutCPUTemp; }