diff --git a/src/com/stuypulse/stuylib/network/SmartAngle.java b/src/com/stuypulse/stuylib/network/SmartAngle.java deleted file mode 100644 index 8a8f61f9..00000000 --- a/src/com/stuypulse/stuylib/network/SmartAngle.java +++ /dev/null @@ -1,142 +0,0 @@ -/* Copyright (c) 2023 StuyPulse Robotics. All rights reserved. */ -/* This work is licensed under the terms of the MIT license */ -/* found in the root directory of this project. */ - -package com.stuypulse.stuylib.network; - -import com.stuypulse.stuylib.math.Angle; -import com.stuypulse.stuylib.util.Conversion; - -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.networktables.DoubleEntry; -import edu.wpi.first.networktables.DoubleTopic; -import edu.wpi.first.networktables.NetworkTableInstance; -import java.util.function.Supplier; - -/** - * SmartAngle works as a wrapper for numbers on the network. This class handles converting a double - * on the network to an Angle - * - * @author Myles Pasetsky (myles.pasetsky@gmail.com) - */ -public class SmartAngle implements Supplier { - - // Built-in conversions from network doubles to Angles - public static final Conversion kDegrees = - Conversion.make(Angle::fromDegrees, a -> a.toDegrees()); - public static final Conversion kRadians = - Conversion.make(Angle::fromRadians, a -> a.toRadians()); - - // network table entry and its default value - private DoubleEntry mEntry; - private Angle mDefaultValue; - - // the double<->angle conversion being used by this smart angle - private Conversion mConversion; - - // the angle from the network value, updated only when network value changes - private Angle mAngle; - - /** - * Create a SmartAngle with a DoubleEntry and a default angle value - * - * @param entry entry to wrap - * @param value default angle value - */ - public SmartAngle(DoubleEntry entry, Angle value) { - useDegrees(); - - mEntry = entry; - mDefaultValue = value; - mAngle = value; - mEntry.setDefault(mConversion.from(mDefaultValue)); - } - - /** - * Create a SmartAngle with a DoubleTopic and a default angle value - * - * @param topic topic to wrap - * @param value default angle value - */ - public SmartAngle(DoubleTopic topic, Angle value) { - useDegrees(); - - mEntry = topic.getEntry(mConversion.from(value)); - mDefaultValue = value; - mAngle = value; - mEntry.setDefault(mConversion.from(mDefaultValue)); - } - - /** - * Create a SmartAngle with a network entry key and a default angle value - * - * @param id network entry key - * @param value default value - */ - public SmartAngle(String id, Angle value) { - this( - NetworkTableInstance.getDefault().getTable("SmartDashboard").getDoubleTopic(id), - value); - } - - /** - * Sets the conversion from the double stored on the network to an Angle class (e.g. sets what - * unit the double on the network is in) - * - * @param conversion conversion between Double and Angle - * @return reference to this - */ - public SmartAngle useConversion(Conversion conversion) { - mConversion = conversion; - return this; - } - - /** - * Sets the unit of the network double to be radians - * - * @return reference to this - */ - public SmartAngle useRadians() { - return useConversion(kRadians); - } - - /** - * Sets the unit of the network double to be degrees - * - * @return reference to this - */ - public SmartAngle useDegrees() { - return useConversion(kDegrees); - } - - /** @return the angle stored by the SmartAngle */ - public Angle getAngle() { - return mAngle; - } - - /** @return the angle stored by the SmartAngle as a Rotation2d */ - public Rotation2d getRotation2d() { - return getAngle().getRotation2d(); - } - - /** @return the angle stored by the SmartAngle */ - @Override - public Angle get() { - return getAngle(); - } - - /** @param angle angle to set SmartAngle to */ - public void set(Angle angle) { - mEntry.set(mConversion.from(angle)); - } - - /** resets the SmartAngle to its default value */ - public void reset() { - set(mDefaultValue); - } - - /** @return the default value of the SmartAngle */ - public Angle getDefault() { - return mDefaultValue; - } -} diff --git a/src/com/stuypulse/stuylib/network/SmartBoolean.java b/src/com/stuypulse/stuylib/network/SmartBoolean.java index e372f162..fae9459e 100644 --- a/src/com/stuypulse/stuylib/network/SmartBoolean.java +++ b/src/com/stuypulse/stuylib/network/SmartBoolean.java @@ -6,9 +6,7 @@ import com.stuypulse.stuylib.streams.booleans.BStream; -import edu.wpi.first.networktables.BooleanEntry; -import edu.wpi.first.networktables.BooleanTopic; -import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; /** @@ -21,41 +19,11 @@ public class SmartBoolean implements BStream { /** The ID / Name for the value on {@link SmartDashboard}. */ - private final BooleanEntry mEntry; + private final int mHandle; /** The default value that the {@link SmartDashboard} value was set too. */ private final boolean mDefaultValue; - /** - * Creates a {@link SmartBoolean} with a BooleanEntry instead of a value for {@link - * SmartDashboard}. This allows you to put items on things like {@link - * edu.wpi.first.wpilibj.shuffleboard.Shuffleboard}, without having to use a raw {@link - * BooleanEntry}. - * - * @param entry the {@link BooleanEntry} the {@link SmartBoolean} should be set to. - * @param value the default value of the {@link SmartBoolean} - */ - public SmartBoolean(BooleanEntry entry, boolean value) { - mEntry = entry; - mDefaultValue = value; - entry.setDefault(value); - } - - /** - * Creates a {@link SmartBoolean} with a BooleanTopic instead of a value for {@link - * SmartDashboard}. This allows you to put items on things like {@link - * edu.wpi.first.wpilibj.shuffleboard.Shuffleboard}, without having to use a raw {@link - * BooleanTopic}. - * - * @param topic the {@link BooleanTopic} the {@link SmartBoolean} should be set to. - * @param value the default value of the {@link SmartBoolean} - */ - public SmartBoolean(BooleanTopic topic, boolean value) { - mEntry = topic.getEntry(value); - mDefaultValue = value; - mEntry.setDefault(value); - } - /** * Creates a {@link SmartBoolean} with the element name and a default value. The value on {@link * SmartDashboard} will be reset to the default value on initialization. @@ -64,14 +32,14 @@ public SmartBoolean(BooleanTopic topic, boolean value) { * @param value the default / initialization value for the value */ public SmartBoolean(String id, boolean value) { - this( - NetworkTableInstance.getDefault().getTable("SmartDashboard").getBooleanTopic(id), - value); + mHandle = NetworkTablesJNI.getEntry(NetworkTablesJNI.getDefaultInstance(), "SmartDashboard/" + id); + mDefaultValue = value; + reset(); } /** @return the value of the boolean from {@link SmartDashboard} */ public boolean get() { - return mEntry.get(mDefaultValue); + return NetworkTablesJNI.getBoolean(mHandle, mDefaultValue); } /** @return the default value of the boolean */ @@ -81,7 +49,7 @@ public boolean getDefault() { /** @param value what the value on {@link SmartDashboard} will be set to */ public void set(boolean value) { - mEntry.set(value); + NetworkTablesJNI.setBoolean(mHandle, 0, value); } /** Resets the value on {@link SmartDashboard} to the default value */ diff --git a/src/com/stuypulse/stuylib/network/SmartNumber.java b/src/com/stuypulse/stuylib/network/SmartNumber.java index 16737541..32e22608 100644 --- a/src/com/stuypulse/stuylib/network/SmartNumber.java +++ b/src/com/stuypulse/stuylib/network/SmartNumber.java @@ -6,9 +6,7 @@ import com.stuypulse.stuylib.streams.IStream; -import edu.wpi.first.networktables.DoubleEntry; -import edu.wpi.first.networktables.DoubleTopic; -import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; /** @@ -18,46 +16,16 @@ * * @author Sam (sam.belliveau@gmail.com) */ -public class SmartNumber extends Number implements IStream { +public final class SmartNumber extends Number implements IStream { private static final long serialVersionUID = 1L; /** The ID / Name for the value on {@link SmartDashboard}. */ - private final DoubleEntry mEntry; + private final int mHandle; /** The default value that the {@link SmartDashboard} value was set too. */ private final double mDefaultValue; - /** - * Creates a {@link SmartNumber} with a DoubleEntry instead of a value for {@link - * SmartDashboard}. This allows you to put items on things like {@link - * edu.wpi.first.wpilibj.shuffleboard.Shuffleboard}, without having to use a raw {@link - * DoubleEntry}. - * - * @param entry the {@link DoubleEntry} the {@link SmartNumber} should be set to. - * @param value the default value of the {@link SmartNumber} - */ - public SmartNumber(DoubleEntry entry, double value) { - mEntry = entry; - mDefaultValue = value; - mEntry.setDefault(value); - } - - /** - * Creates a {@link SmartNumber} with a DoubleTopic instead of a value for {@link - * SmartDashboard}. This allows you to put items on things like {@link - * edu.wpi.first.wpilibj.shuffleboard.Shuffleboard}, without having to use a raw {@link - * DoubleTopic}. - * - * @param topic the {@link DoubleTopic} the {@link SmartNumber} should be set to. - * @param value the default value of the {@link SmartNumber} - */ - public SmartNumber(DoubleTopic topic, double value) { - mEntry = topic.getEntry(value); - mDefaultValue = value; - mEntry.setDefault(value); - } - /** * Creates a SmartNumber with the element name and a default value. The value on {@link * SmartDashboard} will be reset to the default value on initialization. @@ -66,14 +34,14 @@ public SmartNumber(DoubleTopic topic, double value) { * @param value the default / initialization value for the value */ public SmartNumber(String id, double value) { - this( - NetworkTableInstance.getDefault().getTable("SmartDashboard").getDoubleTopic(id), - value); + mHandle = NetworkTablesJNI.getEntry(NetworkTablesJNI.getDefaultInstance(), "SmartDashboard/" + id); + mDefaultValue = value; + reset(); } /** @return the value of the number from SmartDashboard */ public double get() { - return mEntry.get(); + return NetworkTablesJNI.getDouble(mHandle, mDefaultValue); } /** @return the default value of the number */ @@ -83,7 +51,7 @@ public double getDefault() { /** @param value what the value on {@link SmartDashboard} will be set to */ public void set(Number value) { - mEntry.set(value.doubleValue()); + NetworkTablesJNI.setDouble(mHandle, 0, value.doubleValue()); } /** Resets the value on {@link SmartDashboard} to the default value */ diff --git a/src/com/stuypulse/stuylib/network/SmartString.java b/src/com/stuypulse/stuylib/network/SmartString.java index 415e87cc..e996a326 100644 --- a/src/com/stuypulse/stuylib/network/SmartString.java +++ b/src/com/stuypulse/stuylib/network/SmartString.java @@ -4,9 +4,7 @@ package com.stuypulse.stuylib.network; -import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.networktables.StringEntry; -import edu.wpi.first.networktables.StringTopic; +import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import java.util.function.Supplier; @@ -20,41 +18,11 @@ public class SmartString implements Supplier { /** The ID / Name for the value on {@link SmartDashboard}. */ - private final StringEntry mEntry; + private final int mHandle; /** The default value that the {@link SmartDashboard} value was set too. */ private final String mDefaultValue; - /** - * Creates a {@link SmartString} with a StringEntry instead of a value for {@link - * SmartDashboard}. This allows you to put items on things like {@link - * edu.wpi.first.wpilibj.shuffleboard.Shuffleboard}, without having to use a raw {@link - * StringEntry}. - * - * @param entry the {@link StringEntry} the {@link SmartString} should be set to. - * @param value the default value of the {@link SmartString} - */ - public SmartString(StringEntry entry, String value) { - mEntry = entry; - mDefaultValue = value; - mEntry.setDefault(value); - } - - /** - * Creates a {@link SmartString} with a StringTopic instead of a value for {@link - * SmartDashboard}. This allows you to put items on things like {@link - * edu.wpi.first.wpilibj.shuffleboard.Shuffleboard}, without having to use a raw {@link - * StringTopic}. - * - * @param topic the {@link StringTopic} the {@link SmartString} should be set to. - * @param value the default value of the {@link SmartString} - */ - public SmartString(StringTopic topic, String value) { - mEntry = topic.getEntry(value); - mDefaultValue = value; - mEntry.setDefault(value); - } - /** * Creates a SmartString with the element name and a default value. The value on {@link * SmartDashboard} will be reset to the default value on initialization. @@ -63,14 +31,14 @@ public SmartString(StringTopic topic, String value) { * @param value the default / initialization value for the value */ public SmartString(String id, String value) { - this( - NetworkTableInstance.getDefault().getTable("SmartDashboard").getStringTopic(id), - value); + mHandle = NetworkTablesJNI.getEntry(NetworkTablesJNI.getDefaultInstance(), "SmartDashboard/" + value); + mDefaultValue = value; + reset(); } /** @return the value of the String from SmartDashboard */ public String get() { - return mEntry.get(mDefaultValue); + return NetworkTablesJNI.getString(mHandle, mDefaultValue); } /** @return the default value of the String */ @@ -80,7 +48,7 @@ public String getDefault() { /** @param value what the value on {@link SmartDashboard} will be set to */ public void set(String value) { - mEntry.set(value); + NetworkTablesJNI.setString(mHandle, 0, value); } /** Resets the value on {@link SmartDashboard} to the default value */