mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Update wpilibj to use new NetworkTables package and interfaces.
This may be breaking to CANSpeedController implementations.
This commit is contained in:
@@ -10,13 +10,14 @@ package edu.wpi.first.wpilibj;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* ADXL345 I2C Accelerometer.
|
||||
@@ -174,25 +175,44 @@ public class ADXL345_I2C extends SensorBase implements Accelerometer, LiveWindow
|
||||
return "3AxisAccelerometer";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_xEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_yEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_zEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("X", getX());
|
||||
m_table.putNumber("Y", getY());
|
||||
m_table.putNumber("Z", getZ());
|
||||
m_xEntry = m_table.getEntry("X");
|
||||
m_yEntry = m_table.getEntry("Y");
|
||||
m_zEntry = m_table.getEntry("Z");
|
||||
updateTable();
|
||||
} else {
|
||||
m_xEntry = null;
|
||||
m_yEntry = null;
|
||||
m_zEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_xEntry != null) {
|
||||
m_xEntry.setDouble(getX());
|
||||
}
|
||||
if (m_yEntry != null) {
|
||||
m_yEntry.setDouble(getY());
|
||||
}
|
||||
if (m_zEntry != null) {
|
||||
m_zEntry.setDouble(getZ());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -10,13 +10,14 @@ package edu.wpi.first.wpilibj;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* ADXL345 SPI Accelerometer.
|
||||
@@ -192,25 +193,44 @@ public class ADXL345_SPI extends SensorBase implements Accelerometer, LiveWindow
|
||||
return "3AxisAccelerometer";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_xEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_yEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_zEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("X", getX());
|
||||
m_table.putNumber("Y", getY());
|
||||
m_table.putNumber("Z", getZ());
|
||||
m_xEntry = m_table.getEntry("X");
|
||||
m_yEntry = m_table.getEntry("Y");
|
||||
m_zEntry = m_table.getEntry("Z");
|
||||
updateTable();
|
||||
} else {
|
||||
m_xEntry = null;
|
||||
m_yEntry = null;
|
||||
m_zEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_xEntry != null) {
|
||||
m_xEntry.setDouble(getX());
|
||||
}
|
||||
if (m_yEntry != null) {
|
||||
m_yEntry.setDouble(getY());
|
||||
}
|
||||
if (m_zEntry != null) {
|
||||
m_zEntry.setDouble(getZ());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -10,12 +10,13 @@ package edu.wpi.first.wpilibj;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* ADXL362 SPI Accelerometer.
|
||||
@@ -208,25 +209,44 @@ public class ADXL362 extends SensorBase implements Accelerometer, LiveWindowSend
|
||||
return "3AxisAccelerometer";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_xEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_yEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_zEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("X", getX());
|
||||
m_table.putNumber("Y", getY());
|
||||
m_table.putNumber("Z", getZ());
|
||||
m_xEntry = m_table.getEntry("X");
|
||||
m_yEntry = m_table.getEntry("Y");
|
||||
m_zEntry = m_table.getEntry("Z");
|
||||
updateTable();
|
||||
} else {
|
||||
m_xEntry = null;
|
||||
m_yEntry = null;
|
||||
m_zEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_xEntry != null) {
|
||||
m_xEntry.setDouble(getX());
|
||||
}
|
||||
if (m_yEntry != null) {
|
||||
m_yEntry.setDouble(getY());
|
||||
}
|
||||
if (m_zEntry != null) {
|
||||
m_zEntry.setDouble(getZ());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,11 +7,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
|
||||
@@ -140,23 +141,29 @@ public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWi
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getAcceleration());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(getAcceleration());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -10,12 +10,13 @@ package edu.wpi.first.wpilibj;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
|
||||
/**
|
||||
@@ -364,23 +365,29 @@ public class AnalogInput extends SensorBase implements PIDSource, LiveWindowSend
|
||||
return "Analog Input";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getAverageVoltage());
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(getAverageVoltage());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,12 +7,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.AnalogJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Analog output class.
|
||||
@@ -69,23 +70,29 @@ public class AnalogOutput extends SensorBase implements LiveWindowSendable {
|
||||
return "Analog Output";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getVoltage());
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(getVoltage());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,9 +7,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.interfaces.Potentiometer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Class for reading analog potentiometers. Analog potentiometers read in an analog voltage that
|
||||
@@ -152,23 +153,29 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable {
|
||||
return "Analog Input";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", get());
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(get());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,13 +7,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.AccelerometerJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Built-in accelerometer.
|
||||
@@ -97,25 +98,44 @@ public class BuiltInAccelerometer implements Accelerometer, LiveWindowSendable {
|
||||
return "3AxisAccelerometer";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_xEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_yEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_zEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("X", getX());
|
||||
m_table.putNumber("Y", getY());
|
||||
m_table.putNumber("Z", getZ());
|
||||
m_xEntry = m_table.getEntry("X");
|
||||
m_yEntry = m_table.getEntry("Y");
|
||||
m_zEntry = m_table.getEntry("Z");
|
||||
updateTable();
|
||||
} else {
|
||||
m_xEntry = null;
|
||||
m_yEntry = null;
|
||||
m_zEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_xEntry != null) {
|
||||
m_xEntry.setDouble(getX());
|
||||
}
|
||||
if (m_yEntry != null) {
|
||||
m_yEntry.setDouble(getY());
|
||||
}
|
||||
if (m_zEntry != null) {
|
||||
m_zEntry.setDouble(getZ());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
public interface CANSpeedController extends SpeedController, PIDInterface, LiveWindowSendable {
|
||||
/**
|
||||
@@ -143,19 +143,19 @@ public interface CANSpeedController extends SpeedController, PIDInterface, LiveW
|
||||
|
||||
@Override
|
||||
default void updateTable() {
|
||||
ITable table = getTable();
|
||||
NetworkTable table = getTable();
|
||||
if (table != null) {
|
||||
table.putString("~TYPE~", SMART_DASHBOARD_TYPE);
|
||||
table.putString("Type", getClass().getSimpleName());
|
||||
table.putNumber("Mode", getControlMode().getValue());
|
||||
table.getEntry("~TYPE~").setString(SMART_DASHBOARD_TYPE);
|
||||
table.getEntry("Type").setString(getClass().getSimpleName());
|
||||
table.getEntry("Mode").setDouble(getControlMode().getValue());
|
||||
if (getControlMode().isPID()) {
|
||||
table.putNumber("p", getP());
|
||||
table.putNumber("i", getI());
|
||||
table.putNumber("d", getD());
|
||||
table.putNumber("f", getF());
|
||||
table.getEntry("p").setDouble(getP());
|
||||
table.getEntry("i").setDouble(getI());
|
||||
table.getEntry("d").setDouble(getD());
|
||||
table.getEntry("f").setDouble(getF());
|
||||
}
|
||||
table.putBoolean("Enabled", isEnabled());
|
||||
table.putNumber("Value", get());
|
||||
table.getEntry("Enabled").setBoolean(isEnabled());
|
||||
table.getEntry("Value").setDouble(get());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -165,46 +165,69 @@ public interface CANSpeedController extends SpeedController, PIDInterface, LiveW
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an ITableListener for the LiveWindow table for this CAN speed controller.
|
||||
* Remove table listeners.
|
||||
*/
|
||||
default ITableListener createTableListener() {
|
||||
return (table, key, value, isNew) -> {
|
||||
switch (key) {
|
||||
case "Enabled":
|
||||
if ((Boolean) value) {
|
||||
enable();
|
||||
} else {
|
||||
disable();
|
||||
}
|
||||
break;
|
||||
case "Value":
|
||||
set((Double) value);
|
||||
break;
|
||||
case "Mode":
|
||||
setControlMode(((Double) value).intValue());
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if (getControlMode().isPID()) {
|
||||
switch (key) {
|
||||
case "p":
|
||||
setP((Double) value);
|
||||
break;
|
||||
case "i":
|
||||
setI((Double) value);
|
||||
break;
|
||||
case "d":
|
||||
setD((Double) value);
|
||||
break;
|
||||
case "f":
|
||||
setF((Double) value);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
default void removeTableListeners(int[] listeners) {
|
||||
NetworkTable table = getTable();
|
||||
if (table != null) {
|
||||
table.getEntry("Mode").removeListener(listeners[0]);
|
||||
table.getEntry("p").removeListener(listeners[1]);
|
||||
table.getEntry("i").removeListener(listeners[2]);
|
||||
table.getEntry("d").removeListener(listeners[3]);
|
||||
table.getEntry("f").removeListener(listeners[4]);
|
||||
table.getEntry("Enabled").removeListener(listeners[5]);
|
||||
table.getEntry("Value").removeListener(listeners[6]);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Create table listeners.
|
||||
*/
|
||||
default int[] createTableListeners() {
|
||||
int[] listeners = new int[7];
|
||||
NetworkTable table = getTable();
|
||||
if (table != null) {
|
||||
listeners[0] = table.getEntry("Mode").addListener(
|
||||
(event) -> setControlMode((int) event.value.getDouble()),
|
||||
EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
listeners[1] = table.getEntry("p").addListener((event) -> {
|
||||
if (getControlMode().isPID()) {
|
||||
setP(event.value.getDouble());
|
||||
}
|
||||
}
|
||||
};
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
listeners[2] = table.getEntry("i").addListener((event) -> {
|
||||
if (getControlMode().isPID()) {
|
||||
setI(event.value.getDouble());
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
listeners[3] = table.getEntry("d").addListener((event) -> {
|
||||
if (getControlMode().isPID()) {
|
||||
setD(event.value.getDouble());
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
listeners[4] = table.getEntry("f").addListener((event) -> {
|
||||
if (getControlMode().isPID()) {
|
||||
setF(event.value.getDouble());
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
listeners[5] = table.getEntry("Enabled").addListener((event) -> {
|
||||
if (event.value.getBoolean()) {
|
||||
enable();
|
||||
} else {
|
||||
disable();
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
listeners[6] = table.getEntry("Value").addListener(
|
||||
(event) -> set(event.value.getDouble()),
|
||||
EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
return listeners;
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -7,9 +7,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.CompressorJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Class for operating a compressor connected to a PCM (Pneumatic Control Module). The PCM will
|
||||
@@ -189,10 +191,23 @@ public class Compressor extends SensorBase implements LiveWindowSendable {
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
if (m_enabledEntry != null) {
|
||||
m_enabledListener = m_enabledEntry.addListener((event) -> {
|
||||
if (event.value.getBoolean()) {
|
||||
start();
|
||||
} else {
|
||||
stop();
|
||||
}
|
||||
}, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
if (m_enabledEntry != null) {
|
||||
m_enabledEntry.removeListener(m_enabledListener);
|
||||
m_enabledListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -200,24 +215,36 @@ public class Compressor extends SensorBase implements LiveWindowSendable {
|
||||
return "Compressor";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_enabledEntry;
|
||||
private NetworkTableEntry m_pressureSwitchEntry;
|
||||
private int m_enabledListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_enabledEntry = m_table.getEntry("Enabled");
|
||||
m_pressureSwitchEntry = m_table.getEntry("Pressure Switch");
|
||||
updateTable();
|
||||
} else {
|
||||
m_enabledEntry = null;
|
||||
m_pressureSwitchEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("Enabled", enabled());
|
||||
m_table.putBoolean("Pressure Switch", getPressureSwitchValue());
|
||||
if (m_enabledEntry != null) {
|
||||
m_enabledEntry.setBoolean(enabled());
|
||||
}
|
||||
if (m_pressureSwitchEntry != null) {
|
||||
m_pressureSwitchEntry.setBoolean(getPressureSwitchValue());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -10,12 +10,13 @@ package edu.wpi.first.wpilibj;
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
|
||||
import edu.wpi.first.wpilibj.hal.CounterJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
|
||||
@@ -556,23 +557,29 @@ public class Counter extends SensorBase implements CounterBase, LiveWindowSendab
|
||||
return "Counter";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", get());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(get());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -7,12 +7,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Class to read a digital input. This class will read digital inputs and return the current value
|
||||
@@ -105,26 +106,31 @@ public class DigitalInput extends DigitalSource implements LiveWindowSendable {
|
||||
return "Digital Input";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("Value", get());
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setBoolean(get());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,12 +7,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* Class to write digital outputs. This class will write digital outputs. Other devices that are
|
||||
@@ -204,19 +205,25 @@ public class DigitalOutput extends DigitalSource implements LiveWindowSendable {
|
||||
return "Digital Output";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_tableListener;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
private int m_valueListener;
|
||||
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@@ -229,14 +236,15 @@ public class DigitalOutput extends DigitalSource implements LiveWindowSendable {
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
m_tableListener = (source, key, value, isNew) -> set((boolean) value);
|
||||
m_table.addTableListener("Value", m_tableListener, true);
|
||||
m_valueListener = m_valueEntry.addListener((event) -> set(event.value.getBoolean()),
|
||||
EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
m_valueListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.hal.SolenoidJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* DoubleSolenoid class for running 2 channels of high voltage Digital Output on the PCM.
|
||||
@@ -175,46 +176,52 @@ public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
|
||||
return "Double Solenoid";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_tableListener;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
private int m_valueListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putString("Value", get().name().substring(1));
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setString(get().name().substring(1));
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
set(Value.kOff); // Stop for safety
|
||||
m_tableListener = (source, key, value, isNew) -> {
|
||||
if ("Reverse".equals(value.toString())) {
|
||||
m_valueListener = m_valueEntry.addListener((event) -> {
|
||||
String value = event.value.getString();
|
||||
if ("Reverse".equals(value)) {
|
||||
set(Value.kReverse);
|
||||
} else if ("Forward".equals(value.toString())) {
|
||||
} else if ("Forward".equals(value)) {
|
||||
set(Value.kForward);
|
||||
} else {
|
||||
set(Value.kOff);
|
||||
}
|
||||
};
|
||||
m_table.addTableListener("Value", m_tableListener, true);
|
||||
}, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
set(Value.kOff); // Stop for safety
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
m_valueListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,12 +7,13 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.EncoderJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.util.AllocationException;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
@@ -576,25 +577,41 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW
|
||||
return "Encoder";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_speedEntry;
|
||||
private NetworkTableEntry m_distanceEntry;
|
||||
private NetworkTableEntry m_distancePerTickEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_speedEntry = m_table.getEntry("Speed");
|
||||
m_distanceEntry = m_table.getEntry("Distance");
|
||||
m_distancePerTickEntry = m_table.getEntry("Distance per Tick");
|
||||
updateTable();
|
||||
} else {
|
||||
m_speedEntry = null;
|
||||
m_distanceEntry = null;
|
||||
m_distancePerTickEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Speed", getRate());
|
||||
m_table.putNumber("Distance", getDistance());
|
||||
m_table.putNumber("Distance per Tick", EncoderJNI.getEncoderDistancePerPulse(m_encoder));
|
||||
if (m_speedEntry != null) {
|
||||
m_speedEntry.setDouble(getRate());
|
||||
}
|
||||
if (m_distanceEntry != null) {
|
||||
m_distanceEntry.setDouble(getDistance());
|
||||
}
|
||||
if (m_distancePerTickEntry != null) {
|
||||
m_distancePerTickEntry.setDouble(EncoderJNI.getEncoderDistancePerPulse(m_encoder));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -7,9 +7,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* GyroBase is the common base class for Gyro implementations such as AnalogGyro.
|
||||
@@ -59,24 +60,29 @@ public abstract class GyroBase extends SensorBase implements Gyro, PIDSource, Li
|
||||
return "Gyro";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getAngle());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(getAngle());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -11,9 +11,10 @@ import java.util.ArrayDeque;
|
||||
import java.util.Queue;
|
||||
import java.util.TimerTask;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
import edu.wpi.first.wpilibj.util.BoundaryException;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
@@ -226,9 +227,7 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
m_pidInput = null;
|
||||
m_controlLoop = null;
|
||||
}
|
||||
if (m_table != null) {
|
||||
m_table.removeTableListener(m_listener);
|
||||
}
|
||||
removeListeners();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -354,10 +353,14 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
m_I = i;
|
||||
m_D = d;
|
||||
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("p", p);
|
||||
m_table.putNumber("i", i);
|
||||
m_table.putNumber("d", d);
|
||||
if (m_pEntry != null) {
|
||||
m_pEntry.setDouble(p);
|
||||
}
|
||||
if (m_iEntry != null) {
|
||||
m_iEntry.setDouble(i);
|
||||
}
|
||||
if (m_dEntry != null) {
|
||||
m_dEntry.setDouble(d);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -377,11 +380,17 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
m_D = d;
|
||||
m_F = f;
|
||||
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("p", p);
|
||||
m_table.putNumber("i", i);
|
||||
m_table.putNumber("d", d);
|
||||
m_table.putNumber("f", f);
|
||||
if (m_pEntry != null) {
|
||||
m_pEntry.setDouble(p);
|
||||
}
|
||||
if (m_iEntry != null) {
|
||||
m_iEntry.setDouble(i);
|
||||
}
|
||||
if (m_dEntry != null) {
|
||||
m_dEntry.setDouble(d);
|
||||
}
|
||||
if (m_fEntry != null) {
|
||||
m_fEntry.setDouble(f);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -501,8 +510,8 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
m_buf.clear();
|
||||
m_bufTotal = 0;
|
||||
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("setpoint", m_setpoint);
|
||||
if (m_setpointEntry != null) {
|
||||
m_setpointEntry.setDouble(m_setpoint);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -644,8 +653,8 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
public synchronized void enable() {
|
||||
m_enabled = true;
|
||||
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("enabled", true);
|
||||
if (m_enabledEntry != null) {
|
||||
m_enabledEntry.setBoolean(true);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -657,8 +666,8 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
m_pidOutput.pidWrite(0);
|
||||
m_enabled = false;
|
||||
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("enabled", false);
|
||||
if (m_enabledEntry != null) {
|
||||
m_enabledEntry.setBoolean(false);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -686,41 +695,115 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
return "PIDController";
|
||||
}
|
||||
|
||||
private final ITableListener m_listener = (table, key, value, isNew) -> {
|
||||
if (key.equals("p") || key.equals("i") || key.equals("d") || key.equals("f")) {
|
||||
if (getP() != table.getNumber("p", 0.0) || getI() != table.getNumber("i", 0.0)
|
||||
|| getD() != table.getNumber("d", 0.0) || getF() != table.getNumber("f", 0.0)) {
|
||||
setPID(table.getNumber("p", 0.0), table.getNumber("i", 0.0), table.getNumber("d", 0.0),
|
||||
table.getNumber("f", 0.0));
|
||||
}
|
||||
} else if (key.equals("setpoint")) {
|
||||
if (getSetpoint() != (Double) value) {
|
||||
setSetpoint((Double) value);
|
||||
}
|
||||
} else if (key.equals("enabled") && isEnabled() != (Boolean) value) {
|
||||
if ((Boolean) value) {
|
||||
enable();
|
||||
} else {
|
||||
disable();
|
||||
}
|
||||
private NetworkTable m_table;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_pEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_iEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_dEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private NetworkTableEntry m_fEntry;
|
||||
private NetworkTableEntry m_setpointEntry;
|
||||
private NetworkTableEntry m_enabledEntry;
|
||||
@SuppressWarnings("MemberName")
|
||||
private int m_pListener;
|
||||
@SuppressWarnings("MemberName")
|
||||
private int m_iListener;
|
||||
@SuppressWarnings("MemberName")
|
||||
private int m_dListener;
|
||||
@SuppressWarnings("MemberName")
|
||||
private int m_fListener;
|
||||
private int m_setpointListener;
|
||||
private int m_enabledListener;
|
||||
|
||||
private void removeListeners() {
|
||||
if (m_pEntry != null) {
|
||||
m_pEntry.removeListener(m_pListener);
|
||||
}
|
||||
};
|
||||
private ITable m_table;
|
||||
if (m_iEntry != null) {
|
||||
m_iEntry.removeListener(m_iListener);
|
||||
}
|
||||
if (m_dEntry != null) {
|
||||
m_dEntry.removeListener(m_dListener);
|
||||
}
|
||||
if (m_fEntry != null) {
|
||||
m_fEntry.removeListener(m_fListener);
|
||||
}
|
||||
if (m_setpointEntry != null) {
|
||||
m_setpointEntry.removeListener(m_setpointListener);
|
||||
}
|
||||
if (m_enabledEntry != null) {
|
||||
m_enabledEntry.removeListener(m_enabledListener);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initTable(ITable table) {
|
||||
if (this.m_table != null) {
|
||||
m_table.removeTableListener(m_listener);
|
||||
}
|
||||
public void initTable(NetworkTable table) {
|
||||
removeListeners();
|
||||
m_table = table;
|
||||
if (table != null) {
|
||||
table.putNumber("p", getP());
|
||||
table.putNumber("i", getI());
|
||||
table.putNumber("d", getD());
|
||||
table.putNumber("f", getF());
|
||||
table.putNumber("setpoint", getSetpoint());
|
||||
table.putBoolean("enabled", isEnabled());
|
||||
table.addTableListener(m_listener, false);
|
||||
m_pEntry = table.getEntry("p");
|
||||
m_pEntry.setDouble(getP());
|
||||
m_iEntry = table.getEntry("i");
|
||||
m_iEntry.setDouble(getI());
|
||||
m_dEntry = table.getEntry("d");
|
||||
m_dEntry.setDouble(getD());
|
||||
m_fEntry = table.getEntry("f");
|
||||
m_fEntry.setDouble(getF());
|
||||
m_setpointEntry = table.getEntry("setpoint");
|
||||
m_setpointEntry.setDouble(getSetpoint());
|
||||
m_enabledEntry = table.getEntry("enabled");
|
||||
m_enabledEntry.setBoolean(isEnabled());
|
||||
|
||||
m_pListener = m_pEntry.addListener((entry) -> {
|
||||
synchronized (this) {
|
||||
m_P = entry.value.getDouble();
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
m_iListener = m_iEntry.addListener((entry) -> {
|
||||
synchronized (this) {
|
||||
m_I = entry.value.getDouble();
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
m_dListener = m_dEntry.addListener((entry) -> {
|
||||
synchronized (this) {
|
||||
m_D = entry.value.getDouble();
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
m_fListener = m_fEntry.addListener((entry) -> {
|
||||
synchronized (this) {
|
||||
m_F = entry.value.getDouble();
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
m_setpointListener = m_setpointEntry.addListener((entry) -> {
|
||||
double val = entry.value.getDouble();
|
||||
if (getSetpoint() != val) {
|
||||
setSetpoint(val);
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
|
||||
m_enabledListener = m_enabledEntry.addListener((entry) -> {
|
||||
boolean val = entry.value.getBoolean();
|
||||
if (isEnabled() != val) {
|
||||
if (val) {
|
||||
enable();
|
||||
} else {
|
||||
disable();
|
||||
}
|
||||
}
|
||||
}, EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
} else {
|
||||
m_pEntry = null;
|
||||
m_iEntry = null;
|
||||
m_dEntry = null;
|
||||
m_fEntry = null;
|
||||
m_setpointEntry = null;
|
||||
m_enabledEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -744,7 +827,7 @@ public class PIDController implements PIDInterface, LiveWindowSendable, Controll
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,13 +7,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.DIOJNI;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.hal.PWMJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* Class implements the PWM generation in the FPGA.
|
||||
@@ -249,38 +250,44 @@ public class PWM extends SensorBase implements LiveWindowSendable {
|
||||
return "Speed Controller";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_tableListener;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
private int m_valueListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getSpeed());
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public void updateTable() {
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(getSpeed());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
setSpeed(0); // Stop for safety
|
||||
m_tableListener = (source, key, value, isNew) -> setSpeed((double) value);
|
||||
m_table.addTableListener("Value", m_tableListener, true);
|
||||
m_valueListener = m_valueEntry.addListener((event) -> setSpeed(event.value.getDouble()),
|
||||
EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
setSpeed(0); // Stop for safety
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
m_valueListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,9 +7,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.PDPJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* Class for getting voltage, current, temperature, power and energy from the Power Distribution
|
||||
@@ -117,40 +118,46 @@ public class PowerDistributionPanel extends SensorBase implements LiveWindowSend
|
||||
/*
|
||||
* Live Window code, only does anything if live window is activated.
|
||||
*/
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry[] m_chanEntry;
|
||||
private NetworkTableEntry m_voltageEntry;
|
||||
private NetworkTableEntry m_totalCurrentEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_chanEntry = new NetworkTableEntry[16];
|
||||
for (int i = 0; i < m_chanEntry.length; i++) {
|
||||
m_chanEntry[i] = m_table.getEntry("Chan" + i);
|
||||
}
|
||||
m_voltageEntry = m_table.getEntry("Voltage");
|
||||
m_totalCurrentEntry = m_table.getEntry("TotalCurrent");
|
||||
updateTable();
|
||||
} else {
|
||||
m_chanEntry = null;
|
||||
m_voltageEntry = null;
|
||||
m_totalCurrentEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Chan0", getCurrent(0));
|
||||
m_table.putNumber("Chan1", getCurrent(1));
|
||||
m_table.putNumber("Chan2", getCurrent(2));
|
||||
m_table.putNumber("Chan3", getCurrent(3));
|
||||
m_table.putNumber("Chan4", getCurrent(4));
|
||||
m_table.putNumber("Chan5", getCurrent(5));
|
||||
m_table.putNumber("Chan6", getCurrent(6));
|
||||
m_table.putNumber("Chan7", getCurrent(7));
|
||||
m_table.putNumber("Chan8", getCurrent(8));
|
||||
m_table.putNumber("Chan9", getCurrent(9));
|
||||
m_table.putNumber("Chan10", getCurrent(10));
|
||||
m_table.putNumber("Chan11", getCurrent(11));
|
||||
m_table.putNumber("Chan12", getCurrent(12));
|
||||
m_table.putNumber("Chan13", getCurrent(13));
|
||||
m_table.putNumber("Chan14", getCurrent(14));
|
||||
m_table.putNumber("Chan15", getCurrent(15));
|
||||
m_table.putNumber("Voltage", getVoltage());
|
||||
m_table.putNumber("TotalCurrent", getTotalCurrent());
|
||||
if (m_chanEntry != null) {
|
||||
for (int i = 0; i < m_chanEntry.length; i++) {
|
||||
m_chanEntry[i].setDouble(getCurrent(i));
|
||||
}
|
||||
}
|
||||
if (m_voltageEntry != null) {
|
||||
m_voltageEntry.setDouble(getVoltage());
|
||||
}
|
||||
if (m_totalCurrentEntry != null) {
|
||||
m_totalCurrentEntry.setDouble(getTotalCurrent());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -9,11 +9,12 @@ package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.util.Vector;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
|
||||
@@ -44,21 +45,6 @@ public class Preferences {
|
||||
* The network table.
|
||||
*/
|
||||
private final NetworkTable m_table;
|
||||
/**
|
||||
* Listener to set all Preferences values to persistent (for backwards compatibility with old
|
||||
* dashboards).
|
||||
*/
|
||||
private final ITableListener m_listener = new ITableListener() {
|
||||
@Override
|
||||
public void valueChanged(ITable table, String key, Object value, boolean isNew) {
|
||||
// unused
|
||||
}
|
||||
|
||||
@Override
|
||||
public void valueChangedEx(ITable table, String key, Object value, int flags) {
|
||||
table.setPersistent(key);
|
||||
}
|
||||
};
|
||||
|
||||
/**
|
||||
* Returns the preferences instance.
|
||||
@@ -76,8 +62,12 @@ public class Preferences {
|
||||
* Creates a preference class.
|
||||
*/
|
||||
private Preferences() {
|
||||
m_table = NetworkTable.getTable(TABLE_NAME);
|
||||
m_table.addTableListenerEx(m_listener, ITable.NOTIFY_NEW | ITable.NOTIFY_IMMEDIATE);
|
||||
m_table = NetworkTableInstance.getDefault().getTable(TABLE_NAME);
|
||||
// Listener to set all Preferences values to persistent
|
||||
// (for backwards compatibility with old dashboards).
|
||||
m_table.addEntryListener(
|
||||
(table, key, entry, value, flags) -> entry.setPersistent(),
|
||||
EntryListenerFlags.kImmediate | EntryListenerFlags.kNew);
|
||||
HAL.report(tResourceType.kResourceType_Preferences, 0);
|
||||
}
|
||||
|
||||
@@ -99,8 +89,9 @@ public class Preferences {
|
||||
public void putString(String key, String value) {
|
||||
requireNonNull(value, "Provided value was null");
|
||||
|
||||
m_table.putString(key, value);
|
||||
m_table.setPersistent(key);
|
||||
NetworkTableEntry entry = m_table.getEntry(key);
|
||||
entry.setString(value);
|
||||
entry.setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -110,8 +101,9 @@ public class Preferences {
|
||||
* @param value the value
|
||||
*/
|
||||
public void putInt(String key, int value) {
|
||||
m_table.putNumber(key, value);
|
||||
m_table.setPersistent(key);
|
||||
NetworkTableEntry entry = m_table.getEntry(key);
|
||||
entry.setDouble(value);
|
||||
entry.setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -121,8 +113,9 @@ public class Preferences {
|
||||
* @param value the value
|
||||
*/
|
||||
public void putDouble(String key, double value) {
|
||||
m_table.putNumber(key, value);
|
||||
m_table.setPersistent(key);
|
||||
NetworkTableEntry entry = m_table.getEntry(key);
|
||||
entry.setDouble(value);
|
||||
entry.setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -132,8 +125,9 @@ public class Preferences {
|
||||
* @param value the value
|
||||
*/
|
||||
public void putFloat(String key, float value) {
|
||||
m_table.putNumber(key, value);
|
||||
m_table.setPersistent(key);
|
||||
NetworkTableEntry entry = m_table.getEntry(key);
|
||||
entry.setDouble(value);
|
||||
entry.setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -143,8 +137,9 @@ public class Preferences {
|
||||
* @param value the value
|
||||
*/
|
||||
public void putBoolean(String key, boolean value) {
|
||||
m_table.putBoolean(key, value);
|
||||
m_table.setPersistent(key);
|
||||
NetworkTableEntry entry = m_table.getEntry(key);
|
||||
entry.setBoolean(value);
|
||||
entry.setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -154,8 +149,9 @@ public class Preferences {
|
||||
* @param value the value
|
||||
*/
|
||||
public void putLong(String key, long value) {
|
||||
m_table.putNumber(key, value);
|
||||
m_table.setPersistent(key);
|
||||
NetworkTableEntry entry = m_table.getEntry(key);
|
||||
entry.setDouble(value);
|
||||
entry.setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -186,7 +182,7 @@ public class Preferences {
|
||||
* @return either the value in the table, or the backup
|
||||
*/
|
||||
public String getString(String key, String backup) {
|
||||
return m_table.getString(key, backup);
|
||||
return m_table.getEntry(key).getString(backup);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -198,7 +194,7 @@ public class Preferences {
|
||||
* @return either the value in the table, or the backup
|
||||
*/
|
||||
public int getInt(String key, int backup) {
|
||||
return (int) m_table.getNumber(key, backup);
|
||||
return (int) m_table.getEntry(key).getDouble(backup);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -210,7 +206,7 @@ public class Preferences {
|
||||
* @return either the value in the table, or the backup
|
||||
*/
|
||||
public double getDouble(String key, double backup) {
|
||||
return m_table.getNumber(key, backup);
|
||||
return m_table.getEntry(key).getDouble(backup);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -222,7 +218,7 @@ public class Preferences {
|
||||
* @return either the value in the table, or the backup
|
||||
*/
|
||||
public boolean getBoolean(String key, boolean backup) {
|
||||
return m_table.getBoolean(key, backup);
|
||||
return m_table.getEntry(key).getBoolean(backup);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -234,7 +230,7 @@ public class Preferences {
|
||||
* @return either the value in the table, or the backup
|
||||
*/
|
||||
public float getFloat(String key, float backup) {
|
||||
return (float) m_table.getNumber(key, backup);
|
||||
return (float) m_table.getEntry(key).getDouble(backup);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -246,6 +242,6 @@ public class Preferences {
|
||||
* @return either the value in the table, or the backup
|
||||
*/
|
||||
public long getLong(String key, long backup) {
|
||||
return (long) m_table.getNumber(key, backup);
|
||||
return (long) m_table.getEntry(key).getDouble(backup);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.hal.RelayJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
import java.util.Arrays;
|
||||
import java.util.Optional;
|
||||
@@ -336,37 +337,43 @@ public class Relay extends SensorBase implements MotorSafety, LiveWindowSendable
|
||||
return "Relay";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_tableListener;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
private int m_valueListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putString("Value", get().getPrettyValue());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setString(get().getPrettyValue());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
m_tableListener =
|
||||
(source, key, value, isNew) -> set(Value.getValueOf((String) value).orElse(Value.kOff));
|
||||
m_table.addTableListener("Value", m_tableListener, true);
|
||||
m_valueListener = m_valueEntry.addListener(
|
||||
(event) -> set(Value.getValueOf(event.value.getString()).orElse(Value.kOff)),
|
||||
EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
m_valueListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -16,13 +16,13 @@ import java.util.Enumeration;
|
||||
import java.util.jar.Manifest;
|
||||
//import org.opencv.core.Core;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.internal.HardwareHLUsageReporting;
|
||||
import edu.wpi.first.wpilibj.internal.HardwareTimer;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.util.WPILibVersion;
|
||||
|
||||
/**
|
||||
@@ -56,12 +56,11 @@ public abstract class RobotBase {
|
||||
* to put this code into it's own task that loads on boot so ensure that it runs.
|
||||
*/
|
||||
protected RobotBase() {
|
||||
NetworkTable.setNetworkIdentity("Robot");
|
||||
NetworkTable.setPersistentFilename("/home/lvuser/networktables.ini");
|
||||
NetworkTable.setServerMode(); // must be before b
|
||||
NetworkTableInstance inst = NetworkTableInstance.getDefault();
|
||||
inst.setNetworkIdentity("Robot");
|
||||
inst.startServer("/home/lvuser/networktables.ini");
|
||||
m_ds = DriverStation.getInstance();
|
||||
NetworkTable.getTable(""); // forces network tables to initialize
|
||||
NetworkTable.getTable("LiveWindow").getSubTable("~STATUS~").putBoolean("LW Enabled", false);
|
||||
inst.getTable("LiveWindow").getSubTable("~STATUS~").getEntry("LW Enabled").setBoolean(false);
|
||||
|
||||
LiveWindow.setEnabled(false);
|
||||
}
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
|
||||
|
||||
/**
|
||||
@@ -19,14 +19,14 @@ public interface Sendable {
|
||||
*
|
||||
* @param subtable The table to put the values in.
|
||||
*/
|
||||
void initTable(ITable subtable);
|
||||
void initTable(NetworkTable subtable);
|
||||
|
||||
/**
|
||||
* The table that is associated with this {@link Sendable}.
|
||||
*
|
||||
* @return the table that is currently associated with the {@link Sendable}.
|
||||
*/
|
||||
ITable getTable();
|
||||
NetworkTable getTable();
|
||||
|
||||
/**
|
||||
* The string representation of the named data type that will be used by the smart dashboard for
|
||||
|
||||
@@ -7,11 +7,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* Standard hobby style servo.
|
||||
@@ -114,31 +115,37 @@ public class Servo extends PWM {
|
||||
return "Servo";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_tableListener;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
private int m_valueListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", get());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(get());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
m_tableListener = (source, key, value, isNew) -> set((double) value);
|
||||
m_table.addTableListener("Value", m_tableListener, true);
|
||||
m_valueListener = m_valueEntry.addListener((event) -> set(event.value.getDouble()),
|
||||
EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
m_valueListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.hal.SolenoidJNI;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* Solenoid class for running high voltage Digital Output on the PCM.
|
||||
@@ -61,8 +62,8 @@ public class Solenoid extends SolenoidBase implements LiveWindowSendable {
|
||||
public synchronized void free() {
|
||||
SolenoidJNI.freeSolenoidPort(m_solenoidHandle);
|
||||
m_solenoidHandle = 0;
|
||||
if (m_table != null) {
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
}
|
||||
super.free();
|
||||
}
|
||||
@@ -104,38 +105,44 @@ public class Solenoid extends SolenoidBase implements LiveWindowSendable {
|
||||
return "Solenoid";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private ITableListener m_tableListener;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
private int m_valueListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("Value", get());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setBoolean(get());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void startLiveWindowMode() {
|
||||
set(false); // Stop for safety
|
||||
m_tableListener = (source, key, value, isNew) -> set((boolean) value);
|
||||
m_table.addTableListener("Value", m_tableListener, true);
|
||||
m_valueListener = m_valueEntry.addListener((event) -> set(event.value.getBoolean()),
|
||||
EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopLiveWindowMode() {
|
||||
set(false); // Stop for safety
|
||||
// TODO: Broken, should only remove the listener from "Value" only.
|
||||
m_table.removeTableListener(m_tableListener);
|
||||
m_valueEntry.removeListener(m_valueListener);
|
||||
m_valueListener = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,11 +7,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.wpilibj.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
|
||||
@@ -398,23 +399,29 @@ public class Ultrasonic extends SensorBase implements PIDSource, LiveWindowSenda
|
||||
return "Ultrasonic";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_valueEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
updateTable();
|
||||
if (m_table != null) {
|
||||
m_valueEntry = m_table.getEntry("Value");
|
||||
updateTable();
|
||||
} else {
|
||||
m_valueEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void updateTable() {
|
||||
if (m_table != null) {
|
||||
m_table.putNumber("Value", getRangeInches());
|
||||
if (m_valueEntry != null) {
|
||||
m_valueEntry.setDouble(getRangeInches());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -7,26 +7,26 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.buttons;
|
||||
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
|
||||
/**
|
||||
* A {@link Button} that uses a {@link NetworkTable} boolean field.
|
||||
*/
|
||||
public class NetworkButton extends Button {
|
||||
|
||||
private final NetworkTable m_table;
|
||||
private final String m_field;
|
||||
private final NetworkTableEntry m_entry;
|
||||
|
||||
public NetworkButton(String table, String field) {
|
||||
this(NetworkTable.getTable(table), field);
|
||||
this(NetworkTableInstance.getDefault().getTable(table), field);
|
||||
}
|
||||
|
||||
public NetworkButton(NetworkTable table, String field) {
|
||||
m_table = table;
|
||||
m_field = field;
|
||||
m_entry = table.getEntry(field);
|
||||
}
|
||||
|
||||
public boolean get() {
|
||||
return m_table.isConnected() && m_table.getBoolean(m_field, false);
|
||||
return m_entry.getInstance().isConnected() && m_entry.getBoolean(false);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,10 +7,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.buttons;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
import edu.wpi.first.wpilibj.command.Scheduler;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* This class provides an easy way to link commands to inputs.
|
||||
@@ -41,7 +42,7 @@ public abstract class Trigger implements Sendable {
|
||||
*/
|
||||
@SuppressWarnings("PMD.UselessParentheses")
|
||||
private boolean grab() {
|
||||
return get() || (m_table != null && m_table.getBoolean("pressed", false));
|
||||
return get() || (m_pressedEntry != null && m_pressedEntry.getBoolean(false));
|
||||
|
||||
}
|
||||
|
||||
@@ -194,18 +195,22 @@ public abstract class Trigger implements Sendable {
|
||||
return "Button";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_pressedEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable table) {
|
||||
public void initTable(NetworkTable table) {
|
||||
m_table = table;
|
||||
if (table != null) {
|
||||
table.putBoolean("pressed", get());
|
||||
m_pressedEntry = table.getEntry("pressed");
|
||||
m_pressedEntry.setBoolean(get());
|
||||
} else {
|
||||
m_pressedEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -10,11 +10,12 @@ package edu.wpi.first.wpilibj.command;
|
||||
import java.util.Enumeration;
|
||||
import java.util.NoSuchElementException;
|
||||
|
||||
import edu.wpi.first.networktables.EntryListenerFlags;
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.NamedSendable;
|
||||
import edu.wpi.first.wpilibj.RobotState;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
import edu.wpi.first.wpilibj.tables.ITableListener;
|
||||
|
||||
/**
|
||||
* The Command class is at the very core of the entire command framework. Every command can be
|
||||
@@ -216,8 +217,8 @@ public abstract class Command implements NamedSendable {
|
||||
m_initialized = false;
|
||||
m_canceled = false;
|
||||
m_running = false;
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("running", false);
|
||||
if (m_runningEntry != null) {
|
||||
m_runningEntry.setBoolean(false);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -381,8 +382,8 @@ public abstract class Command implements NamedSendable {
|
||||
}
|
||||
lockChanges();
|
||||
m_parent = parent;
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("isParented", true);
|
||||
if (m_isParentedEntry != null) {
|
||||
m_isParentedEntry.setBoolean(true);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -423,8 +424,8 @@ public abstract class Command implements NamedSendable {
|
||||
synchronized void startRunning() {
|
||||
m_running = true;
|
||||
m_startTime = -1;
|
||||
if (m_table != null) {
|
||||
m_table.putBoolean("running", true);
|
||||
if (m_runningEntry != null) {
|
||||
m_runningEntry.setBoolean(true);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -563,31 +564,38 @@ public abstract class Command implements NamedSendable {
|
||||
return "Command";
|
||||
}
|
||||
|
||||
private final ITableListener m_listener = (table1, key, value, isNew) -> {
|
||||
if (((Boolean) value).booleanValue()) {
|
||||
start();
|
||||
} else {
|
||||
cancel();
|
||||
}
|
||||
};
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_runningEntry;
|
||||
private NetworkTableEntry m_isParentedEntry;
|
||||
private int m_runningListener;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable table) {
|
||||
if (m_table != null) {
|
||||
m_table.removeTableListener(m_listener);
|
||||
public void initTable(NetworkTable table) {
|
||||
if (m_runningEntry != null) {
|
||||
m_runningEntry.removeListener(m_runningListener);
|
||||
}
|
||||
m_table = table;
|
||||
if (table != null) {
|
||||
table.putString("name", getName());
|
||||
table.putBoolean("running", isRunning());
|
||||
table.putBoolean("isParented", m_parent != null);
|
||||
table.addTableListener("running", m_listener, false);
|
||||
m_runningEntry = table.getEntry("running");
|
||||
m_isParentedEntry = table.getEntry("isParented");
|
||||
table.getEntry("name").setString(getName());
|
||||
m_runningEntry.setBoolean(isRunning());
|
||||
m_isParentedEntry.setBoolean(m_parent != null);
|
||||
m_runningListener = m_runningEntry.addListener((event) -> {
|
||||
if (event.value.getBoolean()) {
|
||||
start();
|
||||
} else {
|
||||
cancel();
|
||||
}
|
||||
}, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
|
||||
} else {
|
||||
m_runningEntry = null;
|
||||
m_isParentedEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -7,12 +7,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.command;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.PIDController;
|
||||
import edu.wpi.first.wpilibj.PIDOutput;
|
||||
import edu.wpi.first.wpilibj.PIDSource;
|
||||
import edu.wpi.first.wpilibj.PIDSourceType;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* This class defines a {@link Command} which interacts heavily with a PID loop.
|
||||
@@ -213,7 +213,7 @@ public abstract class PIDCommand extends Command implements Sendable {
|
||||
return "PIDCommand";
|
||||
}
|
||||
|
||||
public void initTable(ITable table) {
|
||||
public void initTable(NetworkTable table) {
|
||||
m_controller.initTable(table);
|
||||
super.initTable(table);
|
||||
}
|
||||
|
||||
@@ -7,12 +7,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.command;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.PIDController;
|
||||
import edu.wpi.first.wpilibj.PIDOutput;
|
||||
import edu.wpi.first.wpilibj.PIDSource;
|
||||
import edu.wpi.first.wpilibj.PIDSourceType;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* This class is designed to handle the case where there is a {@link Subsystem} which uses a single
|
||||
@@ -284,7 +284,7 @@ public abstract class PIDSubsystem extends Subsystem implements Sendable {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initTable(ITable table) {
|
||||
public void initTable(NetworkTable table) {
|
||||
m_controller.initTable(table);
|
||||
super.initTable(table);
|
||||
}
|
||||
|
||||
@@ -11,10 +11,11 @@ import java.util.Enumeration;
|
||||
import java.util.Hashtable;
|
||||
import java.util.Vector;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.HLUsageReporting;
|
||||
import edu.wpi.first.wpilibj.NamedSendable;
|
||||
import edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* The {@link Scheduler} is a singleton which holds the top-level running commands. It is in charge
|
||||
@@ -72,7 +73,10 @@ public class Scheduler implements NamedSendable {
|
||||
* A list of all {@link Command Commands} which need to be added.
|
||||
*/
|
||||
private Vector<Command> m_additions = new Vector<>();
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_namesEntry;
|
||||
private NetworkTableEntry m_idsEntry;
|
||||
private NetworkTableEntry m_cancelEntry;
|
||||
/**
|
||||
* A list of all {@link edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler Buttons}. It is
|
||||
* created lazily.
|
||||
@@ -310,18 +314,26 @@ public class Scheduler implements NamedSendable {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initTable(ITable subtable) {
|
||||
public void initTable(NetworkTable subtable) {
|
||||
m_table = subtable;
|
||||
|
||||
m_table.putStringArray("Names", new String[0]);
|
||||
m_table.putNumberArray("Ids", new double[0]);
|
||||
m_table.putNumberArray("Cancel", new double[0]);
|
||||
if (m_table != null) {
|
||||
m_namesEntry = m_table.getEntry("Names");
|
||||
m_idsEntry = m_table.getEntry("Ids");
|
||||
m_cancelEntry = m_table.getEntry("Cancel");
|
||||
m_namesEntry.setStringArray(new String[0]);
|
||||
m_idsEntry.setDoubleArray(new double[0]);
|
||||
m_cancelEntry.setDoubleArray(new double[0]);
|
||||
} else {
|
||||
m_namesEntry = null;
|
||||
m_idsEntry = null;
|
||||
m_cancelEntry = null;
|
||||
}
|
||||
}
|
||||
|
||||
private void updateTable() {
|
||||
if (m_table != null) {
|
||||
// Get the commands to cancel
|
||||
double[] toCancel = m_table.getNumberArray("Cancel", new double[0]);
|
||||
double[] toCancel = m_cancelEntry.getDoubleArray(new double[0]);
|
||||
if (toCancel.length > 0) {
|
||||
for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
|
||||
for (double d : toCancel) {
|
||||
@@ -330,7 +342,7 @@ public class Scheduler implements NamedSendable {
|
||||
}
|
||||
}
|
||||
}
|
||||
m_table.putNumberArray("Cancel", new double[0]);
|
||||
m_cancelEntry.setDoubleArray(new double[0]);
|
||||
}
|
||||
|
||||
if (m_runningCommandsChanged) {
|
||||
@@ -347,14 +359,14 @@ public class Scheduler implements NamedSendable {
|
||||
ids[number] = e.getData().hashCode();
|
||||
number++;
|
||||
}
|
||||
m_table.putStringArray("Names", commands);
|
||||
m_table.putNumberArray("Ids", ids);
|
||||
m_namesEntry.setStringArray(commands);
|
||||
m_idsEntry.setDoubleArray(ids);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
|
||||
|
||||
@@ -9,8 +9,9 @@ package edu.wpi.first.wpilibj.command;
|
||||
|
||||
import java.util.Enumeration;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.NamedSendable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* This class defines a major component of the robot.
|
||||
@@ -111,10 +112,10 @@ public abstract class Subsystem implements NamedSendable {
|
||||
}
|
||||
if (m_table != null) {
|
||||
if (m_defaultCommand != null) {
|
||||
m_table.putBoolean("hasDefault", true);
|
||||
m_table.putString("default", m_defaultCommand.getName());
|
||||
m_hasDefaultEntry.setBoolean(true);
|
||||
m_defaultEntry.setString(m_defaultCommand.getName());
|
||||
} else {
|
||||
m_table.putBoolean("hasDefault", false);
|
||||
m_hasDefaultEntry.setBoolean(false);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -151,10 +152,10 @@ public abstract class Subsystem implements NamedSendable {
|
||||
if (m_currentCommandChanged) {
|
||||
if (m_table != null) {
|
||||
if (m_currentCommand != null) {
|
||||
m_table.putBoolean("hasCommand", true);
|
||||
m_table.putString("command", m_currentCommand.getName());
|
||||
m_hasCommandEntry.setBoolean(true);
|
||||
m_commandEntry.setString(m_currentCommand.getName());
|
||||
} else {
|
||||
m_table.putBoolean("hasCommand", false);
|
||||
m_hasCommandEntry.setBoolean(false);
|
||||
}
|
||||
}
|
||||
m_currentCommandChanged = false;
|
||||
@@ -190,29 +191,38 @@ public abstract class Subsystem implements NamedSendable {
|
||||
return "Subsystem";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_hasDefaultEntry;
|
||||
private NetworkTableEntry m_defaultEntry;
|
||||
private NetworkTableEntry m_hasCommandEntry;
|
||||
private NetworkTableEntry m_commandEntry;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable table) {
|
||||
public void initTable(NetworkTable table) {
|
||||
m_table = table;
|
||||
if (table != null) {
|
||||
m_hasDefaultEntry = table.getEntry("hasDefault");
|
||||
m_defaultEntry = table.getEntry("default");
|
||||
m_hasCommandEntry = table.getEntry("hasCommand");
|
||||
m_commandEntry = table.getEntry("command");
|
||||
|
||||
if (m_defaultCommand != null) {
|
||||
table.putBoolean("hasDefault", true);
|
||||
table.putString("default", m_defaultCommand.getName());
|
||||
m_hasDefaultEntry.setBoolean(true);
|
||||
m_defaultEntry.setString(m_defaultCommand.getName());
|
||||
} else {
|
||||
table.putBoolean("hasDefault", false);
|
||||
m_hasDefaultEntry.setBoolean(false);
|
||||
}
|
||||
if (m_currentCommand != null) {
|
||||
table.putBoolean("hasCommand", true);
|
||||
table.putString("command", m_currentCommand.getName());
|
||||
m_hasCommandEntry.setBoolean(true);
|
||||
m_commandEntry.setString(m_currentCommand.getName());
|
||||
} else {
|
||||
table.putBoolean("hasCommand", false);
|
||||
m_hasCommandEntry.setBoolean(false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -11,9 +11,10 @@ import java.util.Enumeration;
|
||||
import java.util.Hashtable;
|
||||
import java.util.Vector;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.command.Scheduler;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
|
||||
/**
|
||||
@@ -25,8 +26,9 @@ public class LiveWindow {
|
||||
private static Vector<LiveWindowSendable> sensors = new Vector<>();
|
||||
// private static Vector actuators = new Vector();
|
||||
private static Hashtable<LiveWindowSendable, LiveWindowComponent> components = new Hashtable<>();
|
||||
private static ITable livewindowTable;
|
||||
private static ITable statusTable;
|
||||
private static NetworkTable livewindowTable;
|
||||
private static NetworkTable statusTable;
|
||||
private static NetworkTableEntry enabledEntry;
|
||||
private static boolean liveWindowEnabled = false;
|
||||
private static boolean firstTime = true;
|
||||
|
||||
@@ -38,19 +40,20 @@ public class LiveWindow {
|
||||
*/
|
||||
private static void initializeLiveWindowComponents() {
|
||||
System.out.println("Initializing the components first time");
|
||||
livewindowTable = NetworkTable.getTable("LiveWindow");
|
||||
livewindowTable = NetworkTableInstance.getDefault().getTable("LiveWindow");
|
||||
statusTable = livewindowTable.getSubTable("~STATUS~");
|
||||
enabledEntry = statusTable.getEntry("LW Enabled");
|
||||
for (Enumeration e = components.keys(); e.hasMoreElements(); ) {
|
||||
LiveWindowSendable component = (LiveWindowSendable) e.nextElement();
|
||||
LiveWindowComponent liveWindowComponent = components.get(component);
|
||||
String subsystem = liveWindowComponent.getSubsystem();
|
||||
String name = liveWindowComponent.getName();
|
||||
System.out.println("Initializing table for '" + subsystem + "' '" + name + "'");
|
||||
livewindowTable.getSubTable(subsystem).putString("~TYPE~", "LW Subsystem");
|
||||
ITable table = livewindowTable.getSubTable(subsystem).getSubTable(name);
|
||||
table.putString("~TYPE~", component.getSmartDashboardType());
|
||||
table.putString("Name", name);
|
||||
table.putString("Subsystem", subsystem);
|
||||
livewindowTable.getSubTable(subsystem).getEntry("~TYPE~").setString("LW Subsystem");
|
||||
NetworkTable table = livewindowTable.getSubTable(subsystem).getSubTable(name);
|
||||
table.getEntry("~TYPE~").setString(component.getSmartDashboardType());
|
||||
table.getEntry("Name").setString(name);
|
||||
table.getEntry("Subsystem").setString(subsystem);
|
||||
component.initTable(table);
|
||||
if (liveWindowComponent.isSensor()) {
|
||||
sensors.addElement(component);
|
||||
@@ -89,7 +92,7 @@ public class LiveWindow {
|
||||
Scheduler.getInstance().enable();
|
||||
}
|
||||
liveWindowEnabled = enabled;
|
||||
statusTable.putBoolean("LW Enabled", enabled);
|
||||
enabledEntry.setBoolean(enabled);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -9,9 +9,10 @@ package edu.wpi.first.wpilibj.smartdashboard;
|
||||
|
||||
import java.util.LinkedHashMap;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.command.Command;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
import static java.util.Objects.requireNonNull;
|
||||
|
||||
@@ -63,8 +64,8 @@ public class SendableChooser<V> implements Sendable {
|
||||
public void addObject(String name, V object) {
|
||||
m_map.put(name, object);
|
||||
|
||||
if (m_table != null) {
|
||||
m_table.putStringArray(OPTIONS, m_map.keySet().toArray(new String[0]));
|
||||
if (m_tableOptions != null) {
|
||||
m_tableOptions.setStringArray(m_map.keySet().toArray(new String[0]));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -80,8 +81,8 @@ public class SendableChooser<V> implements Sendable {
|
||||
requireNonNull(name, "Provided name was null");
|
||||
|
||||
m_defaultChoice = name;
|
||||
if (m_table != null) {
|
||||
m_table.putString(DEFAULT, m_defaultChoice);
|
||||
if (m_tableDefault != null) {
|
||||
m_tableDefault.setString(m_defaultChoice);
|
||||
}
|
||||
addObject(name, object);
|
||||
}
|
||||
@@ -93,7 +94,7 @@ public class SendableChooser<V> implements Sendable {
|
||||
* @return the option selected
|
||||
*/
|
||||
public V getSelected() {
|
||||
String selected = m_table.getString(SELECTED, null);
|
||||
String selected = m_tableSelected.getString(null);
|
||||
return m_map.getOrDefault(selected, m_map.get(m_defaultChoice));
|
||||
}
|
||||
|
||||
@@ -102,21 +103,27 @@ public class SendableChooser<V> implements Sendable {
|
||||
return "String Chooser";
|
||||
}
|
||||
|
||||
private ITable m_table;
|
||||
private NetworkTable m_table;
|
||||
private NetworkTableEntry m_tableDefault;
|
||||
private NetworkTableEntry m_tableSelected;
|
||||
private NetworkTableEntry m_tableOptions;
|
||||
|
||||
@Override
|
||||
public void initTable(ITable table) {
|
||||
public void initTable(NetworkTable table) {
|
||||
m_table = table;
|
||||
if (table != null) {
|
||||
table.putStringArray(OPTIONS, m_map.keySet().toArray(new String[0]));
|
||||
m_tableDefault = table.getEntry(DEFAULT);
|
||||
m_tableSelected = table.getEntry(SELECTED);
|
||||
m_tableOptions = table.getEntry(OPTIONS);
|
||||
m_tableOptions.setStringArray(m_map.keySet().toArray(new String[0]));
|
||||
if (m_defaultChoice != null) {
|
||||
table.putString(DEFAULT, m_defaultChoice);
|
||||
m_tableDefault.setString(m_defaultChoice);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ITable getTable() {
|
||||
public NetworkTable getTable() {
|
||||
return m_table;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -11,11 +11,12 @@ import java.nio.ByteBuffer;
|
||||
import java.util.Hashtable;
|
||||
import java.util.Set;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableEntry;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.HLUsageReporting;
|
||||
import edu.wpi.first.wpilibj.NamedSendable;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.tables.ITable;
|
||||
|
||||
/**
|
||||
* The {@link SmartDashboard} class is the bridge between robot programs and the SmartDashboard on
|
||||
@@ -28,12 +29,13 @@ public class SmartDashboard {
|
||||
/**
|
||||
* The {@link NetworkTable} used by {@link SmartDashboard}.
|
||||
*/
|
||||
private static final NetworkTable table = NetworkTable.getTable("SmartDashboard");
|
||||
private static final NetworkTable table =
|
||||
NetworkTableInstance.getDefault().getTable("SmartDashboard");
|
||||
/**
|
||||
* A table linking tables in the SmartDashboard to the {@link Sendable} objects they
|
||||
* came from.
|
||||
*/
|
||||
private static final Hashtable<ITable, Sendable> tablesToData = new Hashtable<>();
|
||||
private static final Hashtable<NetworkTable, Sendable> tablesToData = new Hashtable<>();
|
||||
|
||||
static {
|
||||
HLUsageReporting.reportSmartDashboard();
|
||||
@@ -48,8 +50,8 @@ public class SmartDashboard {
|
||||
* @throws IllegalArgumentException If key is null
|
||||
*/
|
||||
public static void putData(String key, Sendable data) {
|
||||
ITable dataTable = table.getSubTable(key);
|
||||
dataTable.putString("~TYPE~", data.getSmartDashboardType());
|
||||
NetworkTable dataTable = table.getSubTable(key);
|
||||
dataTable.getEntry("~TYPE~").setString(data.getSmartDashboardType());
|
||||
data.initTable(dataTable);
|
||||
tablesToData.put(dataTable, data);
|
||||
}
|
||||
@@ -77,7 +79,7 @@ public class SmartDashboard {
|
||||
* @throws IllegalArgumentException if the key is null
|
||||
*/
|
||||
public static Sendable getData(String key) {
|
||||
ITable subtable = table.getSubTable(key);
|
||||
NetworkTable subtable = table.getSubTable(key);
|
||||
Sendable data = tablesToData.get(subtable);
|
||||
if (data == null) {
|
||||
throw new IllegalArgumentException("SmartDashboard data does not exist: " + key);
|
||||
@@ -86,6 +88,15 @@ public class SmartDashboard {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the entry for the specified key.
|
||||
* @param key the key name
|
||||
* @return Network table entry.
|
||||
*/
|
||||
public static NetworkTableEntry getEntry(String key) {
|
||||
return table.getEntry(key);
|
||||
}
|
||||
|
||||
/**
|
||||
* Checks the table and tells if it contains the specified key.
|
||||
*
|
||||
@@ -122,7 +133,7 @@ public class SmartDashboard {
|
||||
* @param key the key name
|
||||
*/
|
||||
public static void setPersistent(String key) {
|
||||
table.setPersistent(key);
|
||||
getEntry(key).setPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -132,7 +143,7 @@ public class SmartDashboard {
|
||||
* @param key the key name
|
||||
*/
|
||||
public static void clearPersistent(String key) {
|
||||
table.clearPersistent(key);
|
||||
getEntry(key).clearPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -143,7 +154,7 @@ public class SmartDashboard {
|
||||
* @return True if the value is persistent.
|
||||
*/
|
||||
public static boolean isPersistent(String key) {
|
||||
return table.isPersistent(key);
|
||||
return getEntry(key).isPersistent();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -154,7 +165,7 @@ public class SmartDashboard {
|
||||
* @param flags the flags to set (bitmask)
|
||||
*/
|
||||
public static void setFlags(String key, int flags) {
|
||||
table.setFlags(key, flags);
|
||||
getEntry(key).setFlags(flags);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -165,7 +176,7 @@ public class SmartDashboard {
|
||||
* @param flags the flags to clear (bitmask)
|
||||
*/
|
||||
public static void clearFlags(String key, int flags) {
|
||||
table.clearFlags(key, flags);
|
||||
getEntry(key).clearFlags(flags);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -175,7 +186,7 @@ public class SmartDashboard {
|
||||
* @return the flags, or 0 if the key is not defined
|
||||
*/
|
||||
public static int getFlags(String key) {
|
||||
return table.getFlags(key);
|
||||
return getEntry(key).getFlags();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -195,7 +206,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putBoolean(String key, boolean value) {
|
||||
return table.putBoolean(key, value);
|
||||
return getEntry(key).setBoolean(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -205,7 +216,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultBoolean(String key, boolean defaultValue) {
|
||||
return table.setDefaultBoolean(key, defaultValue);
|
||||
return getEntry(key).setDefaultBoolean(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -217,7 +228,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static boolean getBoolean(String key, boolean defaultValue) {
|
||||
return table.getBoolean(key, defaultValue);
|
||||
return getEntry(key).getBoolean(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -227,7 +238,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putNumber(String key, double value) {
|
||||
return table.putNumber(key, value);
|
||||
return getEntry(key).setDouble(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -237,7 +248,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultNumber(String key, double defaultValue) {
|
||||
return table.setDefaultNumber(key, defaultValue);
|
||||
return getEntry(key).setDefaultDouble(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -249,7 +260,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static double getNumber(String key, double defaultValue) {
|
||||
return table.getNumber(key, defaultValue);
|
||||
return getEntry(key).getDouble(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -259,7 +270,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putString(String key, String value) {
|
||||
return table.putString(key, value);
|
||||
return getEntry(key).setString(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -269,7 +280,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultString(String key, String defaultValue) {
|
||||
return table.setDefaultString(key, defaultValue);
|
||||
return getEntry(key).setDefaultString(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -281,7 +292,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static String getString(String key, String defaultValue) {
|
||||
return table.getString(key, defaultValue);
|
||||
return getEntry(key).getString(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -291,7 +302,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putBooleanArray(String key, boolean[] value) {
|
||||
return table.putBooleanArray(key, value);
|
||||
return getEntry(key).setBooleanArray(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -301,7 +312,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putBooleanArray(String key, Boolean[] value) {
|
||||
return table.putBooleanArray(key, value);
|
||||
return getEntry(key).setBooleanArray(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -311,7 +322,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultBooleanArray(String key, boolean[] defaultValue) {
|
||||
return table.setDefaultBooleanArray(key, defaultValue);
|
||||
return getEntry(key).setDefaultBooleanArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -321,7 +332,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultBooleanArray(String key, Boolean[] defaultValue) {
|
||||
return table.setDefaultBooleanArray(key, defaultValue);
|
||||
return getEntry(key).setDefaultBooleanArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -333,7 +344,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static boolean[] getBooleanArray(String key, boolean[] defaultValue) {
|
||||
return table.getBooleanArray(key, defaultValue);
|
||||
return getEntry(key).getBooleanArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -345,7 +356,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static Boolean[] getBooleanArray(String key, Boolean[] defaultValue) {
|
||||
return table.getBooleanArray(key, defaultValue);
|
||||
return getEntry(key).getBooleanArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -355,7 +366,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putNumberArray(String key, double[] value) {
|
||||
return table.putNumberArray(key, value);
|
||||
return getEntry(key).setDoubleArray(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -365,7 +376,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putNumberArray(String key, Double[] value) {
|
||||
return table.putNumberArray(key, value);
|
||||
return getEntry(key).setNumberArray(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -375,7 +386,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultNumberArray(String key, double[] defaultValue) {
|
||||
return table.setDefaultNumberArray(key, defaultValue);
|
||||
return getEntry(key).setDefaultDoubleArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -385,7 +396,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultNumberArray(String key, Double[] defaultValue) {
|
||||
return table.setDefaultNumberArray(key, defaultValue);
|
||||
return getEntry(key).setDefaultNumberArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -397,7 +408,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static double[] getNumberArray(String key, double[] defaultValue) {
|
||||
return table.getNumberArray(key, defaultValue);
|
||||
return getEntry(key).getDoubleArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -409,7 +420,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static Double[] getNumberArray(String key, Double[] defaultValue) {
|
||||
return table.getNumberArray(key, defaultValue);
|
||||
return getEntry(key).getDoubleArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -419,7 +430,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putStringArray(String key, String[] value) {
|
||||
return table.putStringArray(key, value);
|
||||
return getEntry(key).setStringArray(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -429,7 +440,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultStringArray(String key, String[] defaultValue) {
|
||||
return table.setDefaultStringArray(key, defaultValue);
|
||||
return getEntry(key).setDefaultStringArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -441,7 +452,7 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static String[] getStringArray(String key, String[] defaultValue) {
|
||||
return table.getStringArray(key, defaultValue);
|
||||
return getEntry(key).getStringArray(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -451,7 +462,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putRaw(String key, byte[] value) {
|
||||
return table.putRaw(key, value);
|
||||
return getEntry(key).setRaw(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -462,7 +473,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key already exists with a different type
|
||||
*/
|
||||
public static boolean putRaw(String key, ByteBuffer value, int len) {
|
||||
return table.putRaw(key, value, len);
|
||||
return getEntry(key).setRaw(value, len);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -472,7 +483,7 @@ public class SmartDashboard {
|
||||
* @return False if the table key exists with a different type
|
||||
*/
|
||||
public static boolean setDefaultRaw(String key, byte[] defaultValue) {
|
||||
return table.setDefaultRaw(key, defaultValue);
|
||||
return getEntry(key).setDefaultRaw(defaultValue);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -484,6 +495,6 @@ public class SmartDashboard {
|
||||
* if there is no value associated with the key
|
||||
*/
|
||||
public static byte[] getRaw(String key, byte[] defaultValue) {
|
||||
return table.getRaw(key, defaultValue);
|
||||
return getEntry(key).getRaw(defaultValue);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -21,8 +21,9 @@ import java.util.Arrays;
|
||||
import java.util.Collection;
|
||||
import java.util.logging.Logger;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
|
||||
import edu.wpi.first.wpilibj.test.TestBench;
|
||||
|
||||
@@ -102,7 +103,7 @@ public class PIDTest extends AbstractComsSetup {
|
||||
public void setUp() throws Exception {
|
||||
logger.fine("Setup: " + me.getType());
|
||||
me.setup();
|
||||
m_table = NetworkTable.getTable("TEST_PID");
|
||||
m_table = NetworkTableInstance.getDefault().getTable("TEST_PID");
|
||||
m_controller = new PIDController(k_p, k_i, k_d, me.getEncoder(), me.getMotor());
|
||||
m_controller.initTable(m_table);
|
||||
}
|
||||
@@ -133,11 +134,11 @@ public class PIDTest extends AbstractComsSetup {
|
||||
assertFalse("PID did not begin disabled", m_controller.isEnabled());
|
||||
assertEquals("PID.getError() did not start at " + setpoint, setpoint,
|
||||
m_controller.getError(), 0);
|
||||
assertEquals(k_p, m_table.getNumber("p", 9999999), 0);
|
||||
assertEquals(k_i, m_table.getNumber("i", 9999999), 0);
|
||||
assertEquals(k_d, m_table.getNumber("d", 9999999), 0);
|
||||
assertEquals(setpoint, m_table.getNumber("setpoint", 9999999), 0);
|
||||
assertFalse(m_table.getBoolean("enabled", true));
|
||||
assertEquals(k_p, m_table.getEntry("p").getDouble(9999999), 0);
|
||||
assertEquals(k_i, m_table.getEntry("i").getDouble(9999999), 0);
|
||||
assertEquals(k_d, m_table.getEntry("d").getDouble(9999999), 0);
|
||||
assertEquals(setpoint, m_table.getEntry("setpoint").getDouble(9999999), 0);
|
||||
assertFalse(m_table.getEntry("enabled").getBoolean(true));
|
||||
}
|
||||
|
||||
@Test
|
||||
@@ -148,11 +149,11 @@ public class PIDTest extends AbstractComsSetup {
|
||||
m_controller.setSetpoint(setpoint);
|
||||
m_controller.enable();
|
||||
Timer.delay(.5);
|
||||
assertTrue(m_table.getBoolean("enabled", false));
|
||||
assertTrue(m_table.getEntry("enabled").getBoolean(false));
|
||||
assertTrue(m_controller.isEnabled());
|
||||
assertThat(0.0, is(not(me.getMotor().get())));
|
||||
m_controller.reset();
|
||||
assertFalse(m_table.getBoolean("enabled", true));
|
||||
assertFalse(m_table.getEntry("enabled").getBoolean(true));
|
||||
assertFalse(m_controller.isEnabled());
|
||||
assertEquals(0, me.getMotor().get(), 0);
|
||||
}
|
||||
|
||||
@@ -13,11 +13,12 @@ import org.junit.Test;
|
||||
|
||||
import java.util.logging.Logger;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTable;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.Relay.Direction;
|
||||
import edu.wpi.first.wpilibj.Relay.InvalidValueException;
|
||||
import edu.wpi.first.wpilibj.Relay.Value;
|
||||
import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture;
|
||||
import edu.wpi.first.wpilibj.networktables.NetworkTable;
|
||||
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
|
||||
import edu.wpi.first.wpilibj.test.TestBench;
|
||||
|
||||
@@ -30,7 +31,8 @@ import static org.junit.Assert.assertTrue;
|
||||
*/
|
||||
public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
private static final Logger logger = Logger.getLogger(RelayCrossConnectTest.class.getName());
|
||||
private static final NetworkTable table = NetworkTable.getTable("_RELAY_CROSS_CONNECT_TEST_");
|
||||
private static final NetworkTable table =
|
||||
NetworkTableInstance.getDefault().getTable("_RELAY_CROSS_CONNECT_TEST_");
|
||||
private RelayCrossConnectFixture m_relayFixture;
|
||||
|
||||
|
||||
@@ -57,7 +59,7 @@ public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
assertTrue("Input two was not high when relay set both high", m_relayFixture.getInputTwo()
|
||||
.get());
|
||||
assertEquals(Value.kOn, m_relayFixture.getRelay().get());
|
||||
assertEquals("On", table.getString("Value", ""));
|
||||
assertEquals("On", table.getEntry("Value").getString(""));
|
||||
}
|
||||
|
||||
@Test
|
||||
@@ -71,7 +73,7 @@ public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
.getInputTwo()
|
||||
.get());
|
||||
assertEquals(Value.kForward, m_relayFixture.getRelay().get());
|
||||
assertEquals("Forward", table.getString("Value", ""));
|
||||
assertEquals("Forward", table.getEntry("Value").getString(""));
|
||||
}
|
||||
|
||||
@Test
|
||||
@@ -85,7 +87,7 @@ public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
.getInputTwo()
|
||||
.get());
|
||||
assertEquals(Value.kReverse, m_relayFixture.getRelay().get());
|
||||
assertEquals("Reverse", table.getString("Value", ""));
|
||||
assertEquals("Reverse", table.getEntry("Value").getString(""));
|
||||
}
|
||||
|
||||
@Test
|
||||
@@ -98,7 +100,7 @@ public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
assertTrue("Input two was not high when relay set Value.kOn in kForward Direction",
|
||||
m_relayFixture.getInputTwo().get());
|
||||
assertEquals(Value.kOn, m_relayFixture.getRelay().get());
|
||||
assertEquals("On", table.getString("Value", ""));
|
||||
assertEquals("On", table.getEntry("Value").getString(""));
|
||||
}
|
||||
|
||||
@Test
|
||||
@@ -111,7 +113,7 @@ public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
assertFalse("Input two was not low when relay set Value.kOn in kReverse Direction",
|
||||
m_relayFixture.getInputTwo().get());
|
||||
assertEquals(Value.kOn, m_relayFixture.getRelay().get());
|
||||
assertEquals("On", table.getString("Value", ""));
|
||||
assertEquals("On", table.getEntry("Value").getString(""));
|
||||
}
|
||||
|
||||
@Test(expected = InvalidValueException.class)
|
||||
@@ -132,7 +134,7 @@ public class RelayCrossConnectTest extends AbstractComsSetup {
|
||||
// Initially both outputs should be off
|
||||
assertFalse(m_relayFixture.getInputOne().get());
|
||||
assertFalse(m_relayFixture.getInputTwo().get());
|
||||
assertEquals("Off", table.getString("Value", ""));
|
||||
assertEquals("Off", table.getEntry("Value").getString(""));
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
Reference in New Issue
Block a user