[wpilib] Deprecate getInstance() in favor of static functions (#3440)

Co-authored-by: Noam Zaks <imnoamzaks@gmail.com>
This commit is contained in:
Peter Johnson
2021-06-15 23:06:03 -07:00
committed by GitHub
parent 26ff9371d9
commit 362066a9b7
105 changed files with 1500 additions and 1539 deletions

View File

@@ -150,7 +150,7 @@ public final class Main {
/** Start running the camera. */
public static void startCamera(CameraConfig config) {
System.out.println("Starting camera '" + config.name + "' on " + config.path);
VideoSource camera = CameraServer.getInstance().startAutomaticCapture(config.name, config.path);
VideoSource camera = CameraServer.startAutomaticCapture(config.name, config.path);
Gson gson = new GsonBuilder().create();

View File

@@ -158,8 +158,8 @@ bool ReadConfig() {
void StartCamera(const CameraConfig& config) {
fmt::print("Starting camera '{}' on {}\n", config.name, config.path);
auto camera = frc::CameraServer::GetInstance()->StartAutomaticCapture(
config.name, config.path);
auto camera =
frc::CameraServer::StartAutomaticCapture(config.name, config.path);
camera.SetConfigJson(config.config);
}

View File

@@ -33,6 +33,7 @@ import java.util.concurrent.atomic.AtomicInteger;
* Singleton class for creating and keeping camera servers. Also publishes camera information to
* NetworkTables.
*/
@SuppressWarnings("PMD.UnusedPrivateField")
public final class CameraServer {
public static final int kBasePort = 1181;
@@ -46,8 +47,9 @@ public final class CameraServer {
/**
* Get the CameraServer instance.
*
* @return CameraServer instance
* @deprecated Use the static methods
*/
@Deprecated
public static synchronized CameraServer getInstance() {
if (server == null) {
server = new CameraServer();
@@ -55,18 +57,211 @@ public final class CameraServer {
return server;
}
private final AtomicInteger m_defaultUsbDevice;
private String m_primarySourceName;
private final Map<String, VideoSource> m_sources;
private final Map<String, VideoSink> m_sinks;
private final Map<Integer, NetworkTable> m_tables; // indexed by source handle
private static final AtomicInteger m_defaultUsbDevice = new AtomicInteger();
private static String m_primarySourceName;
private static final Map<String, VideoSource> m_sources = new HashMap<>();
private static final Map<String, VideoSink> m_sinks = new HashMap<>();
private static final Map<Integer, NetworkTable> m_tables =
new HashMap<>(); // indexed by source handle
// source handle indexed by sink handle
private final Map<Integer, Integer> m_fixedSources;
private final NetworkTable m_publishTable;
private final VideoListener m_videoListener; // NOPMD
private final int m_tableListener; // NOPMD
private int m_nextPort;
private String[] m_addresses;
private static final Map<Integer, Integer> m_fixedSources = new HashMap<>();
private static final NetworkTable m_publishTable =
NetworkTableInstance.getDefault().getTable(kPublishName);
// We publish sources to NetworkTables using the following structure:
// "/CameraPublisher/{Source.Name}/" - root
// - "source" (string): Descriptive, prefixed with type (e.g. "usb:0")
// - "streams" (string array): URLs that can be used to stream data
// - "description" (string): Description of the source
// - "connected" (boolean): Whether source is connected
// - "mode" (string): Current video mode
// - "modes" (string array): Available video modes
// - "Property/{Property}" - Property values
// - "PropertyInfo/{Property}" - Property supporting information
// Listener for video events
private static final VideoListener m_videoListener =
new VideoListener(
event -> {
switch (event.kind) {
case kSourceCreated:
{
// Create subtable for the camera
NetworkTable table = m_publishTable.getSubTable(event.name);
m_tables.put(event.sourceHandle, table);
table.getEntry("source").setString(makeSourceValue(event.sourceHandle));
table
.getEntry("description")
.setString(CameraServerJNI.getSourceDescription(event.sourceHandle));
table
.getEntry("connected")
.setBoolean(CameraServerJNI.isSourceConnected(event.sourceHandle));
table
.getEntry("streams")
.setStringArray(getSourceStreamValues(event.sourceHandle));
try {
VideoMode mode = CameraServerJNI.getSourceVideoMode(event.sourceHandle);
table.getEntry("mode").setDefaultString(videoModeToString(mode));
table.getEntry("modes").setStringArray(getSourceModeValues(event.sourceHandle));
} catch (VideoException ignored) {
// Do nothing. Let the other event handlers update this if there is an error.
}
break;
}
case kSourceDestroyed:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("source").setString("");
table.getEntry("streams").setStringArray(new String[0]);
table.getEntry("modes").setStringArray(new String[0]);
}
break;
}
case kSourceConnected:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
// update the description too (as it may have changed)
table
.getEntry("description")
.setString(CameraServerJNI.getSourceDescription(event.sourceHandle));
table.getEntry("connected").setBoolean(true);
}
break;
}
case kSourceDisconnected:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("connected").setBoolean(false);
}
break;
}
case kSourceVideoModesUpdated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("modes").setStringArray(getSourceModeValues(event.sourceHandle));
}
break;
}
case kSourceVideoModeChanged:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("mode").setString(videoModeToString(event.mode));
}
break;
}
case kSourcePropertyCreated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
putSourcePropertyValue(table, event, true);
}
break;
}
case kSourcePropertyValueUpdated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
putSourcePropertyValue(table, event, false);
}
break;
}
case kSourcePropertyChoicesUpdated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
try {
String[] choices =
CameraServerJNI.getEnumPropertyChoices(event.propertyHandle);
table
.getEntry("PropertyInfo/" + event.name + "/choices")
.setStringArray(choices);
} catch (VideoException ignored) {
// ignore
}
}
break;
}
case kSinkSourceChanged:
case kSinkCreated:
case kSinkDestroyed:
case kNetworkInterfacesChanged:
{
m_addresses = CameraServerJNI.getNetworkInterfaces();
updateStreamValues();
break;
}
default:
break;
}
},
0x4fff,
true);
private static final int m_tableListener =
NetworkTableInstance.getDefault()
.addEntryListener(
kPublishName + "/",
event -> {
String relativeKey = event.name.substring(kPublishName.length() + 1);
// get source (sourceName/...)
int subKeyIndex = relativeKey.indexOf('/');
if (subKeyIndex == -1) {
return;
}
String sourceName = relativeKey.substring(0, subKeyIndex);
VideoSource source = m_sources.get(sourceName);
if (source == null) {
return;
}
// get subkey
relativeKey = relativeKey.substring(subKeyIndex + 1);
// handle standard names
String propName;
if ("mode".equals(relativeKey)) {
// reset to current mode
event.getEntry().setString(videoModeToString(source.getVideoMode()));
return;
} else if (relativeKey.startsWith("Property/")) {
propName = relativeKey.substring(9);
} else if (relativeKey.startsWith("RawProperty/")) {
propName = relativeKey.substring(12);
} else {
return; // ignore
}
// everything else is a property
VideoProperty property = source.getProperty(propName);
switch (property.getKind()) {
case kNone:
return;
case kBoolean:
// reset to current setting
event.getEntry().setBoolean(property.get() != 0);
return;
case kInteger:
case kEnum:
// reset to current setting
event.getEntry().setDouble(property.get());
return;
case kString:
// reset to current setting
event.getEntry().setString(property.getString());
return;
default:
return;
}
},
EntryListenerFlags.kImmediate | EntryListenerFlags.kUpdate);
private static int m_nextPort = kBasePort;
private static String[] m_addresses = new String[0];
@SuppressWarnings("MissingJavadocMethod")
private static String makeSourceValue(int source) {
@@ -95,7 +290,7 @@ public final class CameraServer {
}
@SuppressWarnings("MissingJavadocMethod")
private synchronized String[] getSinkStreamValues(int sink) {
private static synchronized String[] getSinkStreamValues(int sink) {
// Ignore all but MjpegServer
if (VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) != VideoSink.Kind.kMjpeg) {
return new String[0];
@@ -125,7 +320,7 @@ public final class CameraServer {
}
@SuppressWarnings("MissingJavadocMethod")
private synchronized String[] getSourceStreamValues(int source) {
private static synchronized String[] getSourceStreamValues(int source) {
// Ignore all but HttpCamera
if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
!= VideoSource.Kind.kHttp) {
@@ -160,7 +355,7 @@ public final class CameraServer {
}
@SuppressWarnings("MissingJavadocMethod")
private synchronized void updateStreamValues() {
private static synchronized void updateStreamValues() {
// Over all the sinks...
for (VideoSink i : m_sinks.values()) {
int sink = i.getHandle();
@@ -304,218 +499,7 @@ public final class CameraServer {
}
}
@SuppressWarnings("MissingJavadocMethod")
private CameraServer() {
m_defaultUsbDevice = new AtomicInteger();
m_sources = new HashMap<>();
m_sinks = new HashMap<>();
m_fixedSources = new HashMap<>();
m_tables = new HashMap<>();
m_publishTable = NetworkTableInstance.getDefault().getTable(kPublishName);
m_nextPort = kBasePort;
m_addresses = new String[0];
// We publish sources to NetworkTables using the following structure:
// "/CameraPublisher/{Source.Name}/" - root
// - "source" (string): Descriptive, prefixed with type (e.g. "usb:0")
// - "streams" (string array): URLs that can be used to stream data
// - "description" (string): Description of the source
// - "connected" (boolean): Whether source is connected
// - "mode" (string): Current video mode
// - "modes" (string array): Available video modes
// - "Property/{Property}" - Property values
// - "PropertyInfo/{Property}" - Property supporting information
// Listener for video events
m_videoListener =
new VideoListener(
event -> {
switch (event.kind) {
case kSourceCreated:
{
// Create subtable for the camera
NetworkTable table = m_publishTable.getSubTable(event.name);
m_tables.put(event.sourceHandle, table);
table.getEntry("source").setString(makeSourceValue(event.sourceHandle));
table
.getEntry("description")
.setString(CameraServerJNI.getSourceDescription(event.sourceHandle));
table
.getEntry("connected")
.setBoolean(CameraServerJNI.isSourceConnected(event.sourceHandle));
table
.getEntry("streams")
.setStringArray(getSourceStreamValues(event.sourceHandle));
try {
VideoMode mode = CameraServerJNI.getSourceVideoMode(event.sourceHandle);
table.getEntry("mode").setDefaultString(videoModeToString(mode));
table
.getEntry("modes")
.setStringArray(getSourceModeValues(event.sourceHandle));
} catch (VideoException ignored) {
// Do nothing. Let the other event handlers update this if there is an error.
}
break;
}
case kSourceDestroyed:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("source").setString("");
table.getEntry("streams").setStringArray(new String[0]);
table.getEntry("modes").setStringArray(new String[0]);
}
break;
}
case kSourceConnected:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
// update the description too (as it may have changed)
table
.getEntry("description")
.setString(CameraServerJNI.getSourceDescription(event.sourceHandle));
table.getEntry("connected").setBoolean(true);
}
break;
}
case kSourceDisconnected:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("connected").setBoolean(false);
}
break;
}
case kSourceVideoModesUpdated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table
.getEntry("modes")
.setStringArray(getSourceModeValues(event.sourceHandle));
}
break;
}
case kSourceVideoModeChanged:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
table.getEntry("mode").setString(videoModeToString(event.mode));
}
break;
}
case kSourcePropertyCreated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
putSourcePropertyValue(table, event, true);
}
break;
}
case kSourcePropertyValueUpdated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
putSourcePropertyValue(table, event, false);
}
break;
}
case kSourcePropertyChoicesUpdated:
{
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
try {
String[] choices =
CameraServerJNI.getEnumPropertyChoices(event.propertyHandle);
table
.getEntry("PropertyInfo/" + event.name + "/choices")
.setStringArray(choices);
} catch (VideoException ignored) {
// ignore
}
}
break;
}
case kSinkSourceChanged:
case kSinkCreated:
case kSinkDestroyed:
case kNetworkInterfacesChanged:
{
m_addresses = CameraServerJNI.getNetworkInterfaces();
updateStreamValues();
break;
}
default:
break;
}
},
0x4fff,
true);
// Listener for NetworkTable events
// We don't currently support changing settings via NT due to
// synchronization issues, so just update to current setting if someone
// else tries to change it.
m_tableListener =
NetworkTableInstance.getDefault()
.addEntryListener(
kPublishName + "/",
event -> {
String relativeKey = event.name.substring(kPublishName.length() + 1);
// get source (sourceName/...)
int subKeyIndex = relativeKey.indexOf('/');
if (subKeyIndex == -1) {
return;
}
String sourceName = relativeKey.substring(0, subKeyIndex);
VideoSource source = m_sources.get(sourceName);
if (source == null) {
return;
}
// get subkey
relativeKey = relativeKey.substring(subKeyIndex + 1);
// handle standard names
String propName;
if ("mode".equals(relativeKey)) {
// reset to current mode
event.getEntry().setString(videoModeToString(source.getVideoMode()));
return;
} else if (relativeKey.startsWith("Property/")) {
propName = relativeKey.substring(9);
} else if (relativeKey.startsWith("RawProperty/")) {
propName = relativeKey.substring(12);
} else {
return; // ignore
}
// everything else is a property
VideoProperty property = source.getProperty(propName);
switch (property.getKind()) {
case kNone:
return;
case kBoolean:
// reset to current setting
event.getEntry().setBoolean(property.get() != 0);
return;
case kInteger:
case kEnum:
// reset to current setting
event.getEntry().setDouble(property.get());
return;
case kString:
// reset to current setting
event.getEntry().setString(property.getString());
return;
default:
return;
}
},
EntryListenerFlags.kImmediate | EntryListenerFlags.kUpdate);
}
private CameraServer() {}
/**
* Start automatically capturing images to send to the dashboard.
@@ -529,7 +513,7 @@ public final class CameraServer {
*
* @return The USB camera capturing images.
*/
public UsbCamera startAutomaticCapture() {
public static UsbCamera startAutomaticCapture() {
UsbCamera camera = startAutomaticCapture(m_defaultUsbDevice.getAndIncrement());
CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
return camera;
@@ -544,7 +528,7 @@ public final class CameraServer {
* @param dev The device number of the camera interface
* @return The USB camera capturing images.
*/
public UsbCamera startAutomaticCapture(int dev) {
public static UsbCamera startAutomaticCapture(int dev) {
UsbCamera camera = new UsbCamera("USB Camera " + dev, dev);
startAutomaticCapture(camera);
CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
@@ -558,7 +542,7 @@ public final class CameraServer {
* @param dev The device number of the camera interface
* @return The USB camera capturing images.
*/
public UsbCamera startAutomaticCapture(String name, int dev) {
public static UsbCamera startAutomaticCapture(String name, int dev) {
UsbCamera camera = new UsbCamera(name, dev);
startAutomaticCapture(camera);
CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
@@ -572,7 +556,7 @@ public final class CameraServer {
* @param path The device path (e.g. "/dev/video0") of the camera
* @return The USB camera capturing images.
*/
public UsbCamera startAutomaticCapture(String name, String path) {
public static UsbCamera startAutomaticCapture(String name, String path) {
UsbCamera camera = new UsbCamera(name, path);
startAutomaticCapture(camera);
CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
@@ -585,7 +569,7 @@ public final class CameraServer {
* @param camera Camera
* @return The MJPEG server serving images from the given camera.
*/
public MjpegServer startAutomaticCapture(VideoSource camera) {
public static MjpegServer startAutomaticCapture(VideoSource camera) {
addCamera(camera);
MjpegServer server = addServer("serve_" + camera.getName());
server.setSource(camera);
@@ -600,7 +584,7 @@ public final class CameraServer {
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
* @return The Axis camera capturing images.
*/
public AxisCamera addAxisCamera(String host) {
public static AxisCamera addAxisCamera(String host) {
return addAxisCamera("Axis Camera", host);
}
@@ -612,7 +596,7 @@ public final class CameraServer {
* @param hosts Array of Camera host IPs/DNS names
* @return The Axis camera capturing images.
*/
public AxisCamera addAxisCamera(String[] hosts) {
public static AxisCamera addAxisCamera(String[] hosts) {
return addAxisCamera("Axis Camera", hosts);
}
@@ -623,7 +607,7 @@ public final class CameraServer {
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
* @return The Axis camera capturing images.
*/
public AxisCamera addAxisCamera(String name, String host) {
public static AxisCamera addAxisCamera(String name, String host) {
AxisCamera camera = new AxisCamera(name, host);
// Create a passthrough MJPEG server for USB access
startAutomaticCapture(camera);
@@ -638,7 +622,7 @@ public final class CameraServer {
* @param hosts Array of Camera host IPs/DNS names
* @return The Axis camera capturing images.
*/
public AxisCamera addAxisCamera(String name, String[] hosts) {
public static AxisCamera addAxisCamera(String name, String[] hosts) {
AxisCamera camera = new AxisCamera(name, hosts);
// Create a passthrough MJPEG server for USB access
startAutomaticCapture(camera);
@@ -654,11 +638,11 @@ public final class CameraServer {
* @param name The name to give the camera
* @return The MJPEG server serving images from the given camera.
*/
public MjpegServer addSwitchedCamera(String name) {
public static MjpegServer addSwitchedCamera(String name) {
// create a dummy CvSource
CvSource source = new CvSource(name, VideoMode.PixelFormat.kMJPEG, 160, 120, 30);
MjpegServer server = startAutomaticCapture(source);
synchronized (this) {
synchronized (CameraServer.class) {
m_fixedSources.put(server.getHandle(), source.getHandle());
}
@@ -674,9 +658,9 @@ public final class CameraServer {
*
* @return OpenCV sink for the primary camera feed
*/
public CvSink getVideo() {
public static CvSink getVideo() {
VideoSource source;
synchronized (this) {
synchronized (CameraServer.class) {
if (m_primarySourceName == null) {
throw new VideoException("no camera available");
}
@@ -695,10 +679,10 @@ public final class CameraServer {
* @param camera Camera (e.g. as returned by startAutomaticCapture).
* @return OpenCV sink for the specified camera
*/
public CvSink getVideo(VideoSource camera) {
public static CvSink getVideo(VideoSource camera) {
String name = "opencv_" + camera.getName();
synchronized (this) {
synchronized (CameraServer.class) {
VideoSink sink = m_sinks.get(name);
if (sink != null) {
VideoSink.Kind kind = sink.getKind();
@@ -722,9 +706,9 @@ public final class CameraServer {
* @param name Camera name
* @return OpenCV sink for the specified camera
*/
public CvSink getVideo(String name) {
public static CvSink getVideo(String name) {
VideoSource source;
synchronized (this) {
synchronized (CameraServer.class) {
source = m_sources.get(name);
if (source == null) {
throw new VideoException("could not find camera " + name);
@@ -742,7 +726,7 @@ public final class CameraServer {
* @param height Height of the image being sent
* @return OpenCV source for the MJPEG stream
*/
public CvSource putVideo(String name, int width, int height) {
public static CvSource putVideo(String name, int width, int height) {
CvSource source = new CvSource(name, VideoMode.PixelFormat.kMJPEG, width, height, 30);
startAutomaticCapture(source);
return source;
@@ -754,9 +738,9 @@ public final class CameraServer {
* @param name Server name
* @return The MJPEG server
*/
public MjpegServer addServer(String name) {
public static MjpegServer addServer(String name) {
int port;
synchronized (this) {
synchronized (CameraServer.class) {
port = m_nextPort;
m_nextPort++;
}
@@ -770,7 +754,7 @@ public final class CameraServer {
* @param port Server port
* @return The MJPEG server
*/
public MjpegServer addServer(String name, int port) {
public static MjpegServer addServer(String name, int port) {
MjpegServer server = new MjpegServer(name, port);
addServer(server);
return server;
@@ -781,8 +765,8 @@ public final class CameraServer {
*
* @param server Server
*/
public void addServer(VideoSink server) {
synchronized (this) {
public static void addServer(VideoSink server) {
synchronized (CameraServer.class) {
m_sinks.put(server.getName(), server);
}
}
@@ -792,8 +776,8 @@ public final class CameraServer {
*
* @param name Server name
*/
public void removeServer(String name) {
synchronized (this) {
public static void removeServer(String name) {
synchronized (CameraServer.class) {
m_sinks.remove(name);
}
}
@@ -806,8 +790,8 @@ public final class CameraServer {
*
* @return The server for the primary camera feed
*/
public VideoSink getServer() {
synchronized (this) {
public static VideoSink getServer() {
synchronized (CameraServer.class) {
if (m_primarySourceName == null) {
throw new VideoException("no camera available");
}
@@ -821,8 +805,8 @@ public final class CameraServer {
* @param name Server name
* @return The server
*/
public VideoSink getServer(String name) {
synchronized (this) {
public static VideoSink getServer(String name) {
synchronized (CameraServer.class) {
return m_sinks.get(name);
}
}
@@ -832,9 +816,9 @@ public final class CameraServer {
*
* @param camera Camera
*/
public void addCamera(VideoSource camera) {
public static void addCamera(VideoSource camera) {
String name = camera.getName();
synchronized (this) {
synchronized (CameraServer.class) {
if (m_primarySourceName == null) {
m_primarySourceName = name;
}
@@ -847,8 +831,8 @@ public final class CameraServer {
*
* @param name Camera name
*/
public void removeCamera(String name) {
synchronized (this) {
public static void removeCamera(String name) {
synchronized (CameraServer.class) {
m_sources.remove(name);
}
}

View File

@@ -44,7 +44,7 @@
*
* {@literal @}Override
* public void robotInit() {
* usbCamera = CameraServer.getInstance().startAutomaticCapture(0);
* usbCamera = CameraServer.startAutomaticCapture(0);
* findTotePipeline = new MyFindTotePipeline();
* findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
* }

View File

@@ -11,7 +11,6 @@
#include <networktables/NetworkTable.h>
#include <networktables/NetworkTableInstance.h>
#include <wpi/DenseMap.h>
#include <wpi/ManagedStatic.h>
#include <wpi/SmallString.h>
#include <wpi/StringExtras.h>
#include <wpi/StringMap.h>
@@ -24,8 +23,9 @@ using namespace frc;
static constexpr char const* kPublishName = "/CameraPublisher";
struct CameraServer::Impl {
Impl();
namespace {
struct Instance {
Instance();
std::shared_ptr<nt::NetworkTable> GetSourceTable(CS_Source source);
std::vector<std::string> GetSinkStreamValues(CS_Sink sink);
std::vector<std::string> GetSourceStreamValues(CS_Source source);
@@ -42,19 +42,20 @@ struct CameraServer::Impl {
nt::NetworkTableInstance::GetDefault().GetTable(kPublishName)};
cs::VideoListener m_videoListener;
int m_tableListener;
int m_nextPort;
int m_nextPort{CameraServer::kBasePort};
std::vector<std::string> m_addresses;
};
} // namespace
static Instance& GetInstance() {
static Instance instance;
return instance;
}
CameraServer* CameraServer::GetInstance() {
struct Creator {
static void* call() { return new CameraServer{}; }
};
struct Deleter {
static void call(void* ptr) { delete static_cast<CameraServer*>(ptr); }
};
static wpi::ManagedStatic<CameraServer, Creator, Deleter> instance;
return &(*instance);
::GetInstance();
static CameraServer instance;
return &instance;
}
static std::string_view MakeSourceValue(CS_Source source,
@@ -91,13 +92,12 @@ static std::string MakeStreamValue(std::string_view address, int port) {
return fmt::format("mjpg:http://{}:{}/?action=stream", address, port);
}
std::shared_ptr<nt::NetworkTable> CameraServer::Impl::GetSourceTable(
CS_Source source) {
std::shared_ptr<nt::NetworkTable> Instance::GetSourceTable(CS_Source source) {
std::scoped_lock lock(m_mutex);
return m_tables.lookup(source);
}
std::vector<std::string> CameraServer::Impl::GetSinkStreamValues(CS_Sink sink) {
std::vector<std::string> Instance::GetSinkStreamValues(CS_Sink sink) {
CS_Status status = 0;
// Ignore all but MjpegServer
@@ -129,8 +129,7 @@ std::vector<std::string> CameraServer::Impl::GetSinkStreamValues(CS_Sink sink) {
return values;
}
std::vector<std::string> CameraServer::Impl::GetSourceStreamValues(
CS_Source source) {
std::vector<std::string> Instance::GetSourceStreamValues(CS_Source source) {
CS_Status status = 0;
// Ignore all but HttpCamera
@@ -164,7 +163,7 @@ std::vector<std::string> CameraServer::Impl::GetSourceStreamValues(
return values;
}
void CameraServer::Impl::UpdateStreamValues() {
void Instance::UpdateStreamValues() {
std::scoped_lock lock(m_mutex);
// Over all the sinks...
for (const auto& i : m_sinks) {
@@ -293,7 +292,7 @@ static void PutSourcePropertyValue(nt::NetworkTable* table,
}
}
CameraServer::Impl::Impl() : m_nextPort(kBasePort) {
Instance::Instance() {
// We publish sources to NetworkTables using the following structure:
// "/CameraPublisher/{Source.Name}/" - root
// - "source" (string): Descriptive, prefixed with type (e.g. "usb:0")
@@ -480,12 +479,9 @@ CameraServer::Impl::Impl() : m_nextPort(kBasePort) {
NT_NOTIFY_IMMEDIATE | NT_NOTIFY_UPDATE);
}
CameraServer::CameraServer() : m_impl(new Impl) {}
CameraServer::~CameraServer() = default;
cs::UsbCamera CameraServer::StartAutomaticCapture() {
cs::UsbCamera camera = StartAutomaticCapture(m_impl->m_defaultUsbDevice++);
cs::UsbCamera camera =
StartAutomaticCapture(::GetInstance().m_defaultUsbDevice++);
auto csShared = GetCameraServerShared();
csShared->ReportUsbCamera(camera.GetHandle());
return camera;
@@ -573,7 +569,7 @@ cs::MjpegServer CameraServer::AddSwitchedCamera(std::string_view name) {
// create a dummy CvSource
cs::CvSource source{name, cs::VideoMode::PixelFormat::kMJPEG, 160, 120, 30};
cs::MjpegServer server = StartAutomaticCapture(source);
m_impl->m_fixedSources[server.GetHandle()] = source.GetHandle();
::GetInstance().m_fixedSources[server.GetHandle()] = source.GetHandle();
return server;
}
@@ -587,16 +583,17 @@ cs::MjpegServer CameraServer::StartAutomaticCapture(
}
cs::CvSink CameraServer::GetVideo() {
auto& inst = ::GetInstance();
cs::VideoSource source;
{
auto csShared = GetCameraServerShared();
std::scoped_lock lock(m_impl->m_mutex);
if (m_impl->m_primarySourceName.empty()) {
std::scoped_lock lock(inst.m_mutex);
if (inst.m_primarySourceName.empty()) {
csShared->SetCameraServerError("no camera available");
return cs::CvSink{};
}
auto it = m_impl->m_sources.find(m_impl->m_primarySourceName);
if (it == m_impl->m_sources.end()) {
auto it = inst.m_sources.find(inst.m_primarySourceName);
if (it == inst.m_sources.end()) {
csShared->SetCameraServerError("no camera available");
return cs::CvSink{};
}
@@ -606,13 +603,14 @@ cs::CvSink CameraServer::GetVideo() {
}
cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera) {
auto& inst = ::GetInstance();
wpi::SmallString<64> name{"opencv_"};
name += camera.GetName();
{
std::scoped_lock lock(m_impl->m_mutex);
auto it = m_impl->m_sinks.find(name);
if (it != m_impl->m_sinks.end()) {
std::scoped_lock lock(inst.m_mutex);
auto it = inst.m_sinks.find(name);
if (it != inst.m_sinks.end()) {
auto kind = it->second.GetKind();
if (kind != cs::VideoSink::kCv) {
auto csShared = GetCameraServerShared();
@@ -631,11 +629,12 @@ cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera) {
}
cs::CvSink CameraServer::GetVideo(std::string_view name) {
auto& inst = ::GetInstance();
cs::VideoSource source;
{
std::scoped_lock lock(m_impl->m_mutex);
auto it = m_impl->m_sources.find(name);
if (it == m_impl->m_sources.end()) {
std::scoped_lock lock(inst.m_mutex);
auto it = inst.m_sources.find(name);
if (it == inst.m_sources.end()) {
auto csShared = GetCameraServerShared();
csShared->SetCameraServerError("could not find camera {}", name);
return cs::CvSink{};
@@ -653,10 +652,11 @@ cs::CvSource CameraServer::PutVideo(std::string_view name, int width,
}
cs::MjpegServer CameraServer::AddServer(std::string_view name) {
auto& inst = ::GetInstance();
int port;
{
std::scoped_lock lock(m_impl->m_mutex);
port = m_impl->m_nextPort++;
std::scoped_lock lock(inst.m_mutex);
port = inst.m_nextPort++;
}
return AddServer(name, port);
}
@@ -668,34 +668,37 @@ cs::MjpegServer CameraServer::AddServer(std::string_view name, int port) {
}
void CameraServer::AddServer(const cs::VideoSink& server) {
std::scoped_lock lock(m_impl->m_mutex);
m_impl->m_sinks.try_emplace(server.GetName(), server);
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.m_mutex);
inst.m_sinks.try_emplace(server.GetName(), server);
}
void CameraServer::RemoveServer(std::string_view name) {
std::scoped_lock lock(m_impl->m_mutex);
m_impl->m_sinks.erase(name);
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.m_mutex);
inst.m_sinks.erase(name);
}
cs::VideoSink CameraServer::GetServer() {
auto& inst = ::GetInstance();
std::string name;
{
std::scoped_lock lock(m_impl->m_mutex);
if (m_impl->m_primarySourceName.empty()) {
std::scoped_lock lock(inst.m_mutex);
if (inst.m_primarySourceName.empty()) {
auto csShared = GetCameraServerShared();
csShared->SetCameraServerError("no camera available");
return cs::VideoSink{};
}
name = fmt::format("serve_{}", m_impl->m_primarySourceName);
name = fmt::format("serve_{}", inst.m_primarySourceName);
}
return GetServer(name);
}
cs::VideoSink CameraServer::GetServer(std::string_view name) {
wpi::SmallString<64> nameBuf;
std::scoped_lock lock(m_impl->m_mutex);
auto it = m_impl->m_sinks.find(name);
if (it == m_impl->m_sinks.end()) {
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.m_mutex);
auto it = inst.m_sinks.find(name);
if (it == inst.m_sinks.end()) {
auto csShared = GetCameraServerShared();
csShared->SetCameraServerError("could not find server {}", name);
return cs::VideoSink{};
@@ -704,26 +707,29 @@ cs::VideoSink CameraServer::GetServer(std::string_view name) {
}
void CameraServer::AddCamera(const cs::VideoSource& camera) {
auto& inst = ::GetInstance();
std::string name = camera.GetName();
std::scoped_lock lock(m_impl->m_mutex);
if (m_impl->m_primarySourceName.empty()) {
m_impl->m_primarySourceName = name;
std::scoped_lock lock(inst.m_mutex);
if (inst.m_primarySourceName.empty()) {
inst.m_primarySourceName = name;
}
m_impl->m_sources.try_emplace(name, camera);
inst.m_sources.try_emplace(name, camera);
}
void CameraServer::RemoveCamera(std::string_view name) {
std::scoped_lock lock(m_impl->m_mutex);
m_impl->m_sources.erase(name);
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.m_mutex);
inst.m_sources.erase(name);
}
void CameraServer::SetSize(int size) {
std::scoped_lock lock(m_impl->m_mutex);
if (m_impl->m_primarySourceName.empty()) {
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.m_mutex);
if (inst.m_primarySourceName.empty()) {
return;
}
auto it = m_impl->m_sources.find(m_impl->m_primarySourceName);
if (it == m_impl->m_sources.end()) {
auto it = inst.m_sources.find(inst.m_primarySourceName);
if (it == inst.m_sources.end()) {
return;
}
if (size == kSize160x120) {

View File

@@ -6,10 +6,10 @@
#include <stdint.h>
#include <memory>
#include <string>
#include <string_view>
#include <wpi/deprecated.h>
#include <wpi/span.h>
#include "cscore.h"
@@ -31,7 +31,9 @@ class CameraServer {
/**
* Get the CameraServer instance.
* @deprecated Use the static methods
*/
WPI_DEPRECATED("Use static methods")
static CameraServer* GetInstance();
/**
@@ -45,7 +47,7 @@ class CameraServer {
* with device 0, creating a camera named "USB Camera 0". Subsequent calls
* increment the device number (e.g. 1, 2, etc).
*/
cs::UsbCamera StartAutomaticCapture();
static cs::UsbCamera StartAutomaticCapture();
/**
* Start automatically capturing images to send to the dashboard.
@@ -55,7 +57,7 @@ class CameraServer {
*
* @param dev The device number of the camera interface
*/
cs::UsbCamera StartAutomaticCapture(int dev);
static cs::UsbCamera StartAutomaticCapture(int dev);
/**
* Start automatically capturing images to send to the dashboard.
@@ -63,7 +65,7 @@ class CameraServer {
* @param name The name to give the camera
* @param dev The device number of the camera interface
*/
cs::UsbCamera StartAutomaticCapture(std::string_view name, int dev);
static cs::UsbCamera StartAutomaticCapture(std::string_view name, int dev);
/**
* Start automatically capturing images to send to the dashboard.
@@ -71,8 +73,8 @@ class CameraServer {
* @param name The name to give the camera
* @param path The device path (e.g. "/dev/video0") of the camera
*/
cs::UsbCamera StartAutomaticCapture(std::string_view name,
std::string_view path);
static cs::UsbCamera StartAutomaticCapture(std::string_view name,
std::string_view path);
/**
* Start automatically capturing images to send to the dashboard from
@@ -80,7 +82,7 @@ class CameraServer {
*
* @param camera Camera
*/
cs::MjpegServer StartAutomaticCapture(const cs::VideoSource& camera);
static cs::MjpegServer StartAutomaticCapture(const cs::VideoSource& camera);
/**
* Adds an Axis IP camera.
@@ -89,7 +91,7 @@ class CameraServer {
*
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
*/
cs::AxisCamera AddAxisCamera(std::string_view host);
static cs::AxisCamera AddAxisCamera(std::string_view host);
/**
* Adds an Axis IP camera.
@@ -98,7 +100,7 @@ class CameraServer {
*
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
*/
cs::AxisCamera AddAxisCamera(const char* host);
static cs::AxisCamera AddAxisCamera(const char* host);
/**
* Adds an Axis IP camera.
@@ -107,7 +109,7 @@ class CameraServer {
*
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
*/
cs::AxisCamera AddAxisCamera(const std::string& host);
static cs::AxisCamera AddAxisCamera(const std::string& host);
/**
* Adds an Axis IP camera.
@@ -116,7 +118,7 @@ class CameraServer {
*
* @param hosts Array of Camera host IPs/DNS names
*/
cs::AxisCamera AddAxisCamera(wpi::span<const std::string> hosts);
static cs::AxisCamera AddAxisCamera(wpi::span<const std::string> hosts);
/**
* Adds an Axis IP camera.
@@ -126,7 +128,7 @@ class CameraServer {
* @param hosts Array of Camera host IPs/DNS names
*/
template <typename T>
cs::AxisCamera AddAxisCamera(std::initializer_list<T> hosts);
static cs::AxisCamera AddAxisCamera(std::initializer_list<T> hosts);
/**
* Adds an Axis IP camera.
@@ -134,7 +136,8 @@ class CameraServer {
* @param name The name to give the camera
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
*/
cs::AxisCamera AddAxisCamera(std::string_view name, std::string_view host);
static cs::AxisCamera AddAxisCamera(std::string_view name,
std::string_view host);
/**
* Adds an Axis IP camera.
@@ -142,7 +145,7 @@ class CameraServer {
* @param name The name to give the camera
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
*/
cs::AxisCamera AddAxisCamera(std::string_view name, const char* host);
static cs::AxisCamera AddAxisCamera(std::string_view name, const char* host);
/**
* Adds an Axis IP camera.
@@ -150,7 +153,8 @@ class CameraServer {
* @param name The name to give the camera
* @param host Camera host IP or DNS name (e.g. "10.x.y.11")
*/
cs::AxisCamera AddAxisCamera(std::string_view name, const std::string& host);
static cs::AxisCamera AddAxisCamera(std::string_view name,
const std::string& host);
/**
* Adds an Axis IP camera.
@@ -158,8 +162,8 @@ class CameraServer {
* @param name The name to give the camera
* @param hosts Array of Camera host IPs/DNS names
*/
cs::AxisCamera AddAxisCamera(std::string_view name,
wpi::span<const std::string> hosts);
static cs::AxisCamera AddAxisCamera(std::string_view name,
wpi::span<const std::string> hosts);
/**
* Adds an Axis IP camera.
@@ -168,8 +172,8 @@ class CameraServer {
* @param hosts Array of Camera host IPs/DNS names
*/
template <typename T>
cs::AxisCamera AddAxisCamera(std::string_view name,
std::initializer_list<T> hosts);
static cs::AxisCamera AddAxisCamera(std::string_view name,
std::initializer_list<T> hosts);
/**
* Adds a virtual camera for switching between two streams. Unlike the
@@ -177,7 +181,7 @@ class CameraServer {
* VideoSource. Calling SetSource() on the returned object can be used
* to switch the actual source of the stream.
*/
cs::MjpegServer AddSwitchedCamera(std::string_view name);
static cs::MjpegServer AddSwitchedCamera(std::string_view name);
/**
* Get OpenCV access to the primary camera feed. This allows you to
@@ -186,7 +190,7 @@ class CameraServer {
* <p>This is only valid to call after a camera feed has been added
* with startAutomaticCapture() or addServer().
*/
cs::CvSink GetVideo();
static cs::CvSink GetVideo();
/**
* Get OpenCV access to the specified camera. This allows you to get
@@ -194,7 +198,7 @@ class CameraServer {
*
* @param camera Camera (e.g. as returned by startAutomaticCapture).
*/
cs::CvSink GetVideo(const cs::VideoSource& camera);
static cs::CvSink GetVideo(const cs::VideoSource& camera);
/**
* Get OpenCV access to the specified camera. This allows you to get
@@ -202,7 +206,7 @@ class CameraServer {
*
* @param name Camera name
*/
cs::CvSink GetVideo(std::string_view name);
static cs::CvSink GetVideo(std::string_view name);
/**
* Create a MJPEG stream with OpenCV input. This can be called to pass custom
@@ -212,35 +216,35 @@ class CameraServer {
* @param width Width of the image being sent
* @param height Height of the image being sent
*/
cs::CvSource PutVideo(std::string_view name, int width, int height);
static cs::CvSource PutVideo(std::string_view name, int width, int height);
/**
* Adds a MJPEG server at the next available port.
*
* @param name Server name
*/
cs::MjpegServer AddServer(std::string_view name);
static cs::MjpegServer AddServer(std::string_view name);
/**
* Adds a MJPEG server.
*
* @param name Server name
*/
cs::MjpegServer AddServer(std::string_view name, int port);
static cs::MjpegServer AddServer(std::string_view name, int port);
/**
* Adds an already created server.
*
* @param server Server
*/
void AddServer(const cs::VideoSink& server);
static void AddServer(const cs::VideoSink& server);
/**
* Removes a server by name.
*
* @param name Server name
*/
void RemoveServer(std::string_view name);
static void RemoveServer(std::string_view name);
/**
* Get server for the primary camera feed.
@@ -248,28 +252,28 @@ class CameraServer {
* This is only valid to call after a camera feed has been added with
* StartAutomaticCapture() or AddServer().
*/
cs::VideoSink GetServer();
static cs::VideoSink GetServer();
/**
* Gets a server by name.
*
* @param name Server name
*/
cs::VideoSink GetServer(std::string_view name);
static cs::VideoSink GetServer(std::string_view name);
/**
* Adds an already created camera.
*
* @param camera Camera
*/
void AddCamera(const cs::VideoSource& camera);
static void AddCamera(const cs::VideoSource& camera);
/**
* Removes a camera by name.
*
* @param name Camera name
*/
void RemoveCamera(std::string_view name);
static void RemoveCamera(std::string_view name);
/**
* Sets the size of the image to use. Use the public kSize constants to set
@@ -280,14 +284,10 @@ class CameraServer {
* StartAutomaticCapture() instead.
* @param size The size to use
*/
void SetSize(int size);
static void SetSize(int size);
private:
CameraServer();
~CameraServer();
struct Impl;
std::unique_ptr<Impl> m_impl;
CameraServer() = default;
};
} // namespace frc

View File

@@ -10,7 +10,7 @@
using namespace frc2;
CommandBase::CommandBase() {
wpi::SendableRegistry::GetInstance().Add(this, GetTypeName(*this));
wpi::SendableRegistry::Add(this, GetTypeName(*this));
}
void CommandBase::AddRequirements(
@@ -31,19 +31,19 @@ wpi::SmallSet<Subsystem*, 4> CommandBase::GetRequirements() const {
}
void CommandBase::SetName(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetName(this, name);
wpi::SendableRegistry::SetName(this, name);
}
std::string CommandBase::GetName() const {
return wpi::SendableRegistry::GetInstance().GetName(this);
return wpi::SendableRegistry::GetName(this);
}
std::string CommandBase::GetSubsystem() const {
return wpi::SendableRegistry::GetInstance().GetSubsystem(this);
return wpi::SendableRegistry::GetSubsystem(this);
}
void CommandBase::SetSubsystem(std::string_view subsystem) {
wpi::SendableRegistry::GetInstance().SetSubsystem(this, subsystem);
wpi::SendableRegistry::SetSubsystem(this, subsystem);
}
void CommandBase::InitSendable(wpi::SendableBuilder& builder) {

View File

@@ -70,20 +70,18 @@ CommandScheduler::CommandScheduler()
}) {
HAL_Report(HALUsageReporting::kResourceType_Command,
HALUsageReporting::kCommand2_Scheduler);
wpi::SendableRegistry::GetInstance().AddLW(this, "Scheduler");
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = [this] {
wpi::SendableRegistry::AddLW(this, "Scheduler");
frc::LiveWindow::SetEnabledCallback([this] {
this->Disable();
this->CancelAll();
};
scheduler->disabled = [this] { this->Enable(); };
});
frc::LiveWindow::SetDisabledCallback([this] { this->Enable(); });
}
CommandScheduler::~CommandScheduler() {
wpi::SendableRegistry::GetInstance().Remove(this);
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = nullptr;
scheduler->disabled = nullptr;
wpi::SendableRegistry::Remove(this);
frc::LiveWindow::SetEnabledCallback(nullptr);
frc::LiveWindow::SetDisabledCallback(nullptr);
std::unique_ptr<Impl>().swap(m_impl);
}

View File

@@ -13,7 +13,7 @@
using namespace frc2;
SubsystemBase::SubsystemBase() {
wpi::SendableRegistry::GetInstance().AddLW(this, GetTypeName(*this));
wpi::SendableRegistry::AddLW(this, GetTypeName(*this));
CommandScheduler::GetInstance().RegisterSubsystem({this});
}
@@ -48,22 +48,21 @@ void SubsystemBase::InitSendable(wpi::SendableBuilder& builder) {
}
std::string SubsystemBase::GetName() const {
return wpi::SendableRegistry::GetInstance().GetName(this);
return wpi::SendableRegistry::GetName(this);
}
void SubsystemBase::SetName(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetName(this, name);
wpi::SendableRegistry::SetName(this, name);
}
std::string SubsystemBase::GetSubsystem() const {
return wpi::SendableRegistry::GetInstance().GetSubsystem(this);
return wpi::SendableRegistry::GetSubsystem(this);
}
void SubsystemBase::SetSubsystem(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetSubsystem(this, name);
wpi::SendableRegistry::SetSubsystem(this, name);
}
void SubsystemBase::AddChild(std::string name, wpi::Sendable* child) {
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddLW(child, GetSubsystem(), name);
wpi::SendableRegistry::AddLW(child, GetSubsystem(), name);
}

View File

@@ -31,8 +31,8 @@ public abstract class CommandTestBase {
DriverStationSim.setEnabled(enabled);
DriverStationSim.notifyNewData();
DriverStation.getInstance().isNewControlData();
while (DriverStation.getInstance().isEnabled() != enabled) {
DriverStation.isNewControlData();
while (DriverStation.isEnabled() != enabled) {
try {
Thread.sleep(1);
} catch (InterruptedException exception) {

View File

@@ -41,7 +41,7 @@ PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
static int instances = 0;
instances++;
HAL_Report(HALUsageReporting::kResourceType_PIDController, instances);
wpi::SendableRegistry::GetInstance().Add(this, "PIDController", instances);
wpi::SendableRegistry::Add(this, "PIDController", instances);
}
double PIDBase::Get() const {

View File

@@ -41,10 +41,10 @@ Command::Command(std::string_view name, units::second_t timeout) {
// If name contains an empty string
if (name.empty()) {
wpi::SendableRegistry::GetInstance().Add(
this, fmt::format("Command_{}", typeid(*this).name()));
wpi::SendableRegistry::Add(this,
fmt::format("Command_{}", typeid(*this).name()));
} else {
wpi::SendableRegistry::GetInstance().Add(this, name);
wpi::SendableRegistry::Add(this, name);
}
}
@@ -278,27 +278,25 @@ void Command::StartTiming() {
}
std::string Command::GetName() const {
return wpi::SendableRegistry::GetInstance().GetName(this);
return wpi::SendableRegistry::GetName(this);
}
void Command::SetName(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetName(this, name);
wpi::SendableRegistry::SetName(this, name);
}
std::string Command::GetSubsystem() const {
return wpi::SendableRegistry::GetInstance().GetSubsystem(this);
return wpi::SendableRegistry::GetSubsystem(this);
}
void Command::SetSubsystem(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetSubsystem(this, name);
wpi::SendableRegistry::SetSubsystem(this, name);
}
void Command::InitSendable(wpi::SendableBuilder& builder) {
builder.SetSmartDashboardType("Command");
builder.AddStringProperty(
".name",
[=] { return wpi::SendableRegistry::GetInstance().GetName(this); },
nullptr);
".name", [=] { return wpi::SendableRegistry::GetName(this); }, nullptr);
builder.AddBooleanProperty(
"running", [=] { return IsRunning(); },
[=](bool value) {

View File

@@ -186,9 +186,9 @@ void Scheduler::InitSendable(nt::NTSendableBuilder& builder) {
if (m_impl->runningCommandsChanged) {
m_impl->commandsBuf.resize(0);
m_impl->idsBuf.resize(0);
auto& registry = wpi::SendableRegistry::GetInstance();
for (const auto& command : m_impl->commands) {
m_impl->commandsBuf.emplace_back(registry.GetName(command));
m_impl->commandsBuf.emplace_back(
wpi::SendableRegistry::GetName(command));
m_impl->idsBuf.emplace_back(command->GetID());
}
nt::NetworkTableEntry(namesEntry).SetStringArray(m_impl->commandsBuf);
@@ -200,20 +200,18 @@ void Scheduler::InitSendable(nt::NTSendableBuilder& builder) {
Scheduler::Scheduler() : m_impl(new Impl) {
HAL_Report(HALUsageReporting::kResourceType_Command,
HALUsageReporting::kCommand_Scheduler);
wpi::SendableRegistry::GetInstance().AddLW(this, "Scheduler");
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = [this] {
wpi::SendableRegistry::AddLW(this, "Scheduler");
frc::LiveWindow::SetEnabledCallback([this] {
this->SetEnabled(false);
this->RemoveAll();
};
scheduler->disabled = [this] { this->SetEnabled(true); };
});
frc::LiveWindow::SetDisabledCallback([this] { this->SetEnabled(true); });
}
Scheduler::~Scheduler() {
wpi::SendableRegistry::GetInstance().Remove(this);
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = nullptr;
scheduler->disabled = nullptr;
wpi::SendableRegistry::Remove(this);
frc::LiveWindow::SetEnabledCallback(nullptr);
frc::LiveWindow::SetDisabledCallback(nullptr);
}
void Scheduler::Impl::Remove(Command* command) {

View File

@@ -15,7 +15,7 @@
using namespace frc;
Subsystem::Subsystem(std::string_view name) {
wpi::SendableRegistry::GetInstance().AddLW(this, name, name);
wpi::SendableRegistry::AddLW(this, name, name);
Scheduler::GetInstance()->RegisterSubsystem(this);
}
@@ -44,7 +44,7 @@ Command* Subsystem::GetDefaultCommand() {
std::string Subsystem::GetDefaultCommandName() {
Command* defaultCommand = GetDefaultCommand();
if (defaultCommand) {
return wpi::SendableRegistry::GetInstance().GetName(defaultCommand);
return wpi::SendableRegistry::GetName(defaultCommand);
} else {
return {};
}
@@ -62,7 +62,7 @@ Command* Subsystem::GetCurrentCommand() const {
std::string Subsystem::GetCurrentCommandName() const {
Command* currentCommand = GetCurrentCommand();
if (currentCommand) {
return wpi::SendableRegistry::GetInstance().GetName(currentCommand);
return wpi::SendableRegistry::GetName(currentCommand);
} else {
return {};
}
@@ -73,19 +73,19 @@ void Subsystem::Periodic() {}
void Subsystem::InitDefaultCommand() {}
std::string Subsystem::GetName() const {
return wpi::SendableRegistry::GetInstance().GetName(this);
return wpi::SendableRegistry::GetName(this);
}
void Subsystem::SetName(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetName(this, name);
wpi::SendableRegistry::SetName(this, name);
}
std::string Subsystem::GetSubsystem() const {
return wpi::SendableRegistry::GetInstance().GetSubsystem(this);
return wpi::SendableRegistry::GetSubsystem(this);
}
void Subsystem::SetSubsystem(std::string_view name) {
wpi::SendableRegistry::GetInstance().SetSubsystem(this, name);
wpi::SendableRegistry::SetSubsystem(this, name);
}
void Subsystem::AddChild(std::string_view name,
@@ -98,8 +98,8 @@ void Subsystem::AddChild(std::string_view name, wpi::Sendable* child) {
}
void Subsystem::AddChild(std::string_view name, wpi::Sendable& child) {
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddLW(&child, registry.GetSubsystem(this), name);
wpi::SendableRegistry::AddLW(&child,
wpi::SendableRegistry::GetSubsystem(this), name);
}
void Subsystem::AddChild(std::shared_ptr<wpi::Sendable> child) {
@@ -111,9 +111,9 @@ void Subsystem::AddChild(wpi::Sendable* child) {
}
void Subsystem::AddChild(wpi::Sendable& child) {
auto& registry = wpi::SendableRegistry::GetInstance();
registry.SetSubsystem(&child, registry.GetSubsystem(this));
registry.EnableLiveWindow(&child);
wpi::SendableRegistry::SetSubsystem(
&child, wpi::SendableRegistry::GetSubsystem(this));
wpi::SendableRegistry::EnableLiveWindow(&child);
}
void Subsystem::ConfirmCommand() {

View File

@@ -29,7 +29,7 @@ ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
HAL_Report(HALUsageReporting::kResourceType_ADXL345,
HALUsageReporting::kADXL345_I2C, 0);
wpi::SendableRegistry::GetInstance().AddLW(this, "ADXL345_I2C", port);
wpi::SendableRegistry::AddLW(this, "ADXL345_I2C", port);
}
void ADXL345_I2C::SetRange(Range range) {

View File

@@ -37,7 +37,7 @@ ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range)
HAL_Report(HALUsageReporting::kResourceType_ADXL345,
HALUsageReporting::kADXL345_SPI);
wpi::SendableRegistry::GetInstance().AddLW(this, "ADXL345_SPI", port);
wpi::SendableRegistry::AddLW(this, "ADXL345_SPI", port);
}
void ADXL345_SPI::SetRange(Range range) {

View File

@@ -72,7 +72,7 @@ ADXL362::ADXL362(SPI::Port port, Range range)
HAL_Report(HALUsageReporting::kResourceType_ADXL362, port + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "ADXL362", port);
wpi::SendableRegistry::AddLW(this, "ADXL362", port);
}
void ADXL362::SetRange(Range range) {

View File

@@ -58,7 +58,7 @@ ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port)
HAL_Report(HALUsageReporting::kResourceType_ADXRS450, port + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "ADXRS450_Gyro", port);
wpi::SendableRegistry::AddLW(this, "ADXRS450_Gyro", port);
}
static bool CalcParity(int v) {

View File

@@ -15,7 +15,7 @@ using namespace frc;
AnalogAccelerometer::AnalogAccelerometer(int channel)
: AnalogAccelerometer(std::make_shared<AnalogInput>(channel)) {
wpi::SendableRegistry::GetInstance().AddChild(this, m_analogInput.get());
wpi::SendableRegistry::AddChild(this, m_analogInput.get());
}
AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
@@ -56,6 +56,6 @@ void AnalogAccelerometer::InitAccelerometer() {
HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
m_analogInput->GetChannel() + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "Accelerometer",
m_analogInput->GetChannel());
wpi::SendableRegistry::AddLW(this, "Accelerometer",
m_analogInput->GetChannel());
}

View File

@@ -50,8 +50,8 @@ void AnalogEncoder::Init() {
m_counter.SetDownSource(
m_analogTrigger.CreateOutput(AnalogTriggerType::kFallingPulse));
wpi::SendableRegistry::GetInstance().AddLW(this, "DutyCycle Encoder",
m_analogInput->GetChannel());
wpi::SendableRegistry::AddLW(this, "DutyCycle Encoder",
m_analogInput->GetChannel());
}
units::turn_t AnalogEncoder::Get() const {

View File

@@ -23,7 +23,7 @@ using namespace frc;
AnalogGyro::AnalogGyro(int channel)
: AnalogGyro(std::make_shared<AnalogInput>(channel)) {
wpi::SendableRegistry::GetInstance().AddChild(this, m_analog.get());
wpi::SendableRegistry::AddChild(this, m_analog.get());
}
AnalogGyro::AnalogGyro(AnalogInput* channel)
@@ -41,7 +41,7 @@ AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
AnalogGyro::AnalogGyro(int channel, int center, double offset)
: AnalogGyro(std::make_shared<AnalogInput>(channel), center, offset) {
wpi::SendableRegistry::GetInstance().AddChild(this, m_analog.get());
wpi::SendableRegistry::AddChild(this, m_analog.get());
}
AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
@@ -124,8 +124,7 @@ void AnalogGyro::InitGyro() {
HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel() + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "AnalogGyro",
m_analog->GetChannel());
wpi::SendableRegistry::AddLW(this, "AnalogGyro", m_analog->GetChannel());
}
void AnalogGyro::Calibrate() {

View File

@@ -34,7 +34,7 @@ AnalogInput::AnalogInput(int channel) {
HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "AnalogInput", channel);
wpi::SendableRegistry::AddLW(this, "AnalogInput", channel);
}
AnalogInput::~AnalogInput() {

View File

@@ -34,7 +34,7 @@ AnalogOutput::AnalogOutput(int channel) {
FRC_CheckErrorStatus(status, "Channel {}", channel);
HAL_Report(HALUsageReporting::kResourceType_AnalogOutput, m_channel + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "AnalogOutput", m_channel);
wpi::SendableRegistry::AddLW(this, "AnalogOutput", m_channel);
}
AnalogOutput::~AnalogOutput() {

View File

@@ -18,7 +18,7 @@ AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
double offset)
: AnalogPotentiometer(std::make_shared<AnalogInput>(channel), fullRange,
offset) {
wpi::SendableRegistry::GetInstance().AddChild(this, m_analog_input.get());
wpi::SendableRegistry::AddChild(this, m_analog_input.get());
}
AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange,
@@ -32,8 +32,8 @@ AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
: m_analog_input(std::move(input)),
m_fullRange(fullRange),
m_offset(offset) {
wpi::SendableRegistry::GetInstance().AddLW(this, "AnalogPotentiometer",
m_analog_input->GetChannel());
wpi::SendableRegistry::AddLW(this, "AnalogPotentiometer",
m_analog_input->GetChannel());
}
double AnalogPotentiometer::Get() const {

View File

@@ -20,7 +20,7 @@ using namespace frc;
AnalogTrigger::AnalogTrigger(int channel)
: AnalogTrigger(new AnalogInput(channel)) {
m_ownsAnalog = true;
wpi::SendableRegistry::GetInstance().AddChild(this, m_analogInput);
wpi::SendableRegistry::AddChild(this, m_analogInput);
}
AnalogTrigger::AnalogTrigger(AnalogInput* input) {
@@ -31,7 +31,7 @@ AnalogTrigger::AnalogTrigger(AnalogInput* input) {
int index = GetIndex();
HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", index);
wpi::SendableRegistry::AddLW(this, "AnalogTrigger", index);
}
AnalogTrigger::AnalogTrigger(DutyCycle* input) {
@@ -42,7 +42,7 @@ AnalogTrigger::AnalogTrigger(DutyCycle* input) {
int index = GetIndex();
HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", index);
wpi::SendableRegistry::AddLW(this, "AnalogTrigger", index);
}
AnalogTrigger::~AnalogTrigger() {

View File

@@ -18,7 +18,7 @@ BuiltInAccelerometer::BuiltInAccelerometer(Range range) {
HAL_Report(HALUsageReporting::kResourceType_Accelerometer, 0, 0,
"Built-in accelerometer");
wpi::SendableRegistry::GetInstance().AddLW(this, "BuiltInAccel");
wpi::SendableRegistry::AddLW(this, "BuiltInAccel");
}
void BuiltInAccelerometer::SetRange(Range range) {

View File

@@ -27,7 +27,7 @@ Counter::Counter(Mode mode) {
SetMaxPeriod(0.5_s);
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1, mode + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "Counter", m_index);
wpi::SendableRegistry::AddLW(this, "Counter", m_index);
}
Counter::Counter(int channel) : Counter(kTwoPulse) {
@@ -97,7 +97,7 @@ Counter::~Counter() {
void Counter::SetUpSource(int channel) {
SetUpSource(std::make_shared<DigitalInput>(channel));
wpi::SendableRegistry::GetInstance().AddChild(this, m_upSource.get());
wpi::SendableRegistry::AddChild(this, m_upSource.get());
}
void Counter::SetUpSource(AnalogTrigger* analogTrigger,
@@ -152,7 +152,7 @@ void Counter::ClearUpSource() {
void Counter::SetDownSource(int channel) {
SetDownSource(std::make_shared<DigitalInput>(channel));
wpi::SendableRegistry::GetInstance().AddChild(this, m_downSource.get());
wpi::SendableRegistry::AddChild(this, m_downSource.get());
}
void Counter::SetDownSource(AnalogTrigger* analogTrigger,

View File

@@ -35,8 +35,7 @@ DigitalGlitchFilter::DigitalGlitchFilter() {
HAL_Report(HALUsageReporting::kResourceType_DigitalGlitchFilter,
m_channelIndex + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "DigitalGlitchFilter",
m_channelIndex);
wpi::SendableRegistry::AddLW(this, "DigitalGlitchFilter", m_channelIndex);
}
DigitalGlitchFilter::~DigitalGlitchFilter() {

View File

@@ -33,7 +33,7 @@ DigitalInput::DigitalInput(int channel) {
FRC_CheckErrorStatus(status, "Channel {}", channel);
HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "DigitalInput", channel);
wpi::SendableRegistry::AddLW(this, "DigitalInput", channel);
}
DigitalInput::~DigitalInput() {

View File

@@ -33,7 +33,7 @@ DigitalOutput::DigitalOutput(int channel) {
FRC_CheckErrorStatus(status, "Channel {}", channel);
HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "DigitalOutput", channel);
wpi::SendableRegistry::AddLW(this, "DigitalOutput", channel);
}
DigitalOutput::~DigitalOutput() {

View File

@@ -53,8 +53,9 @@ DoubleSolenoid::DoubleSolenoid(std::shared_ptr<PneumaticsBase> module,
m_module->GetModuleNumber() + 1);
HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel + 1,
m_module->GetModuleNumber() + 1);
wpi::SendableRegistry::GetInstance().AddLW(
this, "DoubleSolenoid", m_module->GetModuleNumber(), m_forwardChannel);
wpi::SendableRegistry::AddLW(this, "DoubleSolenoid",
m_module->GetModuleNumber(), m_forwardChannel);
}
DoubleSolenoid::~DoubleSolenoid() {}

View File

@@ -4,23 +4,34 @@
#include "frc/DriverStation.h"
#include <stdint.h>
#include <array>
#include <atomic>
#include <chrono>
#include <string>
#include <string_view>
#include <thread>
#include <type_traits>
#include <fmt/format.h>
#include <hal/DriverStation.h>
#include <hal/DriverStationTypes.h>
#include <hal/HALBase.h>
#include <hal/Power.h>
#include <networktables/NetworkTable.h>
#include <networktables/NetworkTableEntry.h>
#include <networktables/NetworkTableInstance.h>
#include <wpi/condition_variable.h>
#include <wpi/mutex.h>
#include "frc/Errors.h"
#include "frc/MotorSafety.h"
#include "frc/Timer.h"
namespace frc {
using namespace frc;
namespace {
// A simple class which caches the previous value written to an NT entry
// Used to prevent redundant, repeated writes of the same value
template <class T>
@@ -60,37 +71,94 @@ class MatchDataSenderEntry {
void SetValue(std::string_view val) { ntEntry.SetString(val); }
};
class MatchDataSender {
public:
std::shared_ptr<nt::NetworkTable> table;
MatchDataSenderEntry<std::string> typeMetaData;
MatchDataSenderEntry<std::string> gameSpecificMessage;
MatchDataSenderEntry<std::string> eventName;
MatchDataSenderEntry<double> matchNumber;
MatchDataSenderEntry<double> replayNumber;
MatchDataSenderEntry<double> matchType;
MatchDataSenderEntry<bool> alliance;
MatchDataSenderEntry<double> station;
MatchDataSenderEntry<double> controlWord;
MatchDataSender()
: table(nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo")),
typeMetaData(table, ".type", "FMSInfo"),
gameSpecificMessage(table, "GameSpecificMessage", ""),
eventName(table, "EventName", ""),
matchNumber(table, "MatchNumber", 0.0),
replayNumber(table, "ReplayNumber", 0.0),
matchType(table, "MatchType", 0.0),
alliance(table, "IsRedAlliance", true),
station(table, "StationNumber", 1.0),
controlWord(table, "FMSControlData", 0.0) {}
struct MatchDataSender {
std::shared_ptr<nt::NetworkTable> table =
nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo");
MatchDataSenderEntry<std::string> typeMetaData{table, ".type", "FMSInfo"};
MatchDataSenderEntry<std::string> gameSpecificMessage{
table, "GameSpecificMessage", ""};
MatchDataSenderEntry<std::string> eventName{table, "EventName", ""};
MatchDataSenderEntry<double> matchNumber{table, "MatchNumber", 0.0};
MatchDataSenderEntry<double> replayNumber{table, "ReplayNumber", 0.0};
MatchDataSenderEntry<double> matchType{table, "MatchType", 0.0};
MatchDataSenderEntry<bool> alliance{table, "IsRedAlliance", true};
MatchDataSenderEntry<double> station{table, "StationNumber", 1.0};
MatchDataSenderEntry<double> controlWord{table, "FMSControlData", 0.0};
};
} // namespace frc
using namespace frc;
struct Instance {
Instance();
~Instance();
MatchDataSender matchDataSender;
// Joystick button rising/falling edge flags
wpi::mutex buttonEdgeMutex;
std::array<HAL_JoystickButtons, DriverStation::kJoystickPorts>
previousButtonStates;
std::array<uint32_t, DriverStation::kJoystickPorts> joystickButtonsPressed;
std::array<uint32_t, DriverStation::kJoystickPorts> joystickButtonsReleased;
// Internal Driver Station thread
std::thread dsThread;
std::atomic<bool> isRunning{false};
mutable wpi::mutex waitForDataMutex;
wpi::condition_variable waitForDataCond;
int waitForDataCounter = 0;
bool silenceJoystickWarning = false;
// Robot state status variables
bool userInDisabled = false;
bool userInAutonomous = false;
bool userInTeleop = false;
bool userInTest = false;
units::second_t nextMessageTime = 0_s;
};
} // namespace
static constexpr auto kJoystickUnpluggedMessageInterval = 1_s;
static Instance& GetInstance() {
static Instance instance;
return instance;
}
static void Run();
static void SendMatchData();
/**
* Reports errors related to unplugged joysticks.
*
* Throttles the errors so that they don't overwhelm the DS.
*/
static void ReportJoystickUnpluggedErrorV(fmt::string_view format,
fmt::format_args args);
template <typename S, typename... Args>
static inline void ReportJoystickUnpluggedError(const S& format,
Args&&... args) {
ReportJoystickUnpluggedErrorV(
format, fmt::make_args_checked<Args...>(format, args...));
}
/**
* Reports errors related to unplugged joysticks.
*
* Throttles the errors so that they don't overwhelm the DS.
*/
static void ReportJoystickUnpluggedWarningV(fmt::string_view format,
fmt::format_args args);
template <typename S, typename... Args>
static inline void ReportJoystickUnpluggedWarning(const S& format,
Args&&... args) {
ReportJoystickUnpluggedWarningV(
format, fmt::make_args_checked<Args...>(format, args...));
}
static int& GetDSLastCount() {
// There is a rollover error condition here. At Packet# = n * (uintmax), this
// will return false when instead it should return true. However, this at a
@@ -100,14 +168,30 @@ static int& GetDSLastCount() {
return lastCount;
}
DriverStation::~DriverStation() {
m_isRunning = false;
Instance::Instance() {
HAL_Initialize(500, 0);
// All joysticks should default to having zero axes, povs and buttons, so
// uninitialized memory doesn't get sent to speed controllers.
for (unsigned int i = 0; i < DriverStation::kJoystickPorts; i++) {
joystickButtonsPressed[i] = 0;
joystickButtonsReleased[i] = 0;
previousButtonStates[i].count = 0;
previousButtonStates[i].buttons = 0;
}
dsThread = std::thread(&Run);
}
Instance::~Instance() {
isRunning = false;
// Trigger a DS mutex release in case there is no driver station running.
HAL_ReleaseDSMutex();
m_dsThread.join();
dsThread.join();
}
DriverStation& DriverStation::GetInstance() {
::GetInstance();
static DriverStation instance;
return instance;
}
@@ -158,14 +242,14 @@ bool DriverStation::GetStickButtonPressed(int stick, int button) {
button, buttons.count);
return false;
}
std::unique_lock lock(m_buttonEdgeMutex);
auto& inst = ::GetInstance();
std::unique_lock lock(inst.buttonEdgeMutex);
// If button was pressed, clear flag and return true
if (m_joystickButtonsPressed[stick] & 1 << (button - 1)) {
m_joystickButtonsPressed[stick] &= ~(1 << (button - 1));
if (inst.joystickButtonsPressed[stick] & 1 << (button - 1)) {
inst.joystickButtonsPressed[stick] &= ~(1 << (button - 1));
return true;
} else {
return false;
}
return false;
}
bool DriverStation::GetStickButtonReleased(int stick, int button) {
@@ -189,14 +273,14 @@ bool DriverStation::GetStickButtonReleased(int stick, int button) {
button, buttons.count);
return false;
}
std::unique_lock lock(m_buttonEdgeMutex);
auto& inst = ::GetInstance();
std::unique_lock lock(inst.buttonEdgeMutex);
// If button was released, clear flag and return true
if (m_joystickButtonsReleased[stick] & 1 << (button - 1)) {
m_joystickButtonsReleased[stick] &= ~(1 << (button - 1));
if (inst.joystickButtonsReleased[stick] & 1 << (button - 1)) {
inst.joystickButtonsReleased[stick] &= ~(1 << (button - 1));
return true;
} else {
return false;
}
return false;
}
double DriverStation::GetStickAxis(int stick, int axis) {
@@ -247,7 +331,7 @@ int DriverStation::GetStickPOV(int stick, int pov) {
return povs.povs[pov];
}
int DriverStation::GetStickButtons(int stick) const {
int DriverStation::GetStickButtons(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -259,7 +343,7 @@ int DriverStation::GetStickButtons(int stick) const {
return buttons.buttons;
}
int DriverStation::GetStickAxisCount(int stick) const {
int DriverStation::GetStickAxisCount(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -271,7 +355,7 @@ int DriverStation::GetStickAxisCount(int stick) const {
return axes.count;
}
int DriverStation::GetStickPOVCount(int stick) const {
int DriverStation::GetStickPOVCount(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -283,7 +367,7 @@ int DriverStation::GetStickPOVCount(int stick) const {
return povs.count;
}
int DriverStation::GetStickButtonCount(int stick) const {
int DriverStation::GetStickButtonCount(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return 0;
@@ -295,7 +379,7 @@ int DriverStation::GetStickButtonCount(int stick) const {
return buttons.count;
}
bool DriverStation::GetJoystickIsXbox(int stick) const {
bool DriverStation::GetJoystickIsXbox(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return false;
@@ -307,7 +391,7 @@ bool DriverStation::GetJoystickIsXbox(int stick) const {
return static_cast<bool>(descriptor.isXbox);
}
int DriverStation::GetJoystickType(int stick) const {
int DriverStation::GetJoystickType(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return -1;
@@ -319,7 +403,7 @@ int DriverStation::GetJoystickType(int stick) const {
return static_cast<int>(descriptor.type);
}
std::string DriverStation::GetJoystickName(int stick) const {
std::string DriverStation::GetJoystickName(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
}
@@ -330,7 +414,7 @@ std::string DriverStation::GetJoystickName(int stick) const {
return descriptor.name;
}
int DriverStation::GetJoystickAxisType(int stick, int axis) const {
int DriverStation::GetJoystickAxisType(int stick, int axis) {
if (stick < 0 || stick >= kJoystickPorts) {
FRC_ReportError(warn::BadJoystickIndex, "stick {} out of range", stick);
return -1;
@@ -342,69 +426,70 @@ int DriverStation::GetJoystickAxisType(int stick, int axis) const {
return static_cast<bool>(descriptor.axisTypes);
}
bool DriverStation::IsJoystickConnected(int stick) const {
bool DriverStation::IsJoystickConnected(int stick) {
return GetStickAxisCount(stick) > 0 || GetStickButtonCount(stick) > 0 ||
GetStickPOVCount(stick) > 0;
}
bool DriverStation::IsEnabled() const {
bool DriverStation::IsEnabled() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.enabled && controlWord.dsAttached;
}
bool DriverStation::IsDisabled() const {
bool DriverStation::IsDisabled() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return !(controlWord.enabled && controlWord.dsAttached);
}
bool DriverStation::IsEStopped() const {
bool DriverStation::IsEStopped() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.eStop;
}
bool DriverStation::IsAutonomous() const {
bool DriverStation::IsAutonomous() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.autonomous;
}
bool DriverStation::IsAutonomousEnabled() const {
bool DriverStation::IsAutonomousEnabled() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.autonomous && controlWord.enabled;
}
bool DriverStation::IsOperatorControl() const {
bool DriverStation::IsOperatorControl() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return !(controlWord.autonomous || controlWord.test);
}
bool DriverStation::IsOperatorControlEnabled() const {
bool DriverStation::IsOperatorControlEnabled() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return !controlWord.autonomous && !controlWord.test && controlWord.enabled;
}
bool DriverStation::IsTest() const {
bool DriverStation::IsTest() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.test;
}
bool DriverStation::IsDSAttached() const {
bool DriverStation::IsDSAttached() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.dsAttached;
}
bool DriverStation::IsNewControlData() const {
std::unique_lock lock(m_waitForDataMutex);
bool DriverStation::IsNewControlData() {
auto& inst = ::GetInstance();
std::unique_lock lock(inst.waitForDataMutex);
int& lastCount = GetDSLastCount();
int currentCount = m_waitForDataCounter;
int currentCount = inst.waitForDataCounter;
if (lastCount == currentCount) {
return false;
}
@@ -412,44 +497,44 @@ bool DriverStation::IsNewControlData() const {
return true;
}
bool DriverStation::IsFMSAttached() const {
bool DriverStation::IsFMSAttached() {
HAL_ControlWord controlWord;
HAL_GetControlWord(&controlWord);
return controlWord.fmsAttached;
}
std::string DriverStation::GetGameSpecificMessage() const {
std::string DriverStation::GetGameSpecificMessage() {
HAL_MatchInfo info;
HAL_GetMatchInfo(&info);
return std::string(reinterpret_cast<char*>(info.gameSpecificMessage),
info.gameSpecificMessageSize);
}
std::string DriverStation::GetEventName() const {
std::string DriverStation::GetEventName() {
HAL_MatchInfo info;
HAL_GetMatchInfo(&info);
return info.eventName;
}
DriverStation::MatchType DriverStation::GetMatchType() const {
DriverStation::MatchType DriverStation::GetMatchType() {
HAL_MatchInfo info;
HAL_GetMatchInfo(&info);
return static_cast<DriverStation::MatchType>(info.matchType);
}
int DriverStation::GetMatchNumber() const {
int DriverStation::GetMatchNumber() {
HAL_MatchInfo info;
HAL_GetMatchInfo(&info);
return info.matchNumber;
}
int DriverStation::GetReplayNumber() const {
int DriverStation::GetReplayNumber() {
HAL_MatchInfo info;
HAL_GetMatchInfo(&info);
return info.replayNumber;
}
DriverStation::Alliance DriverStation::GetAlliance() const {
DriverStation::Alliance DriverStation::GetAlliance() {
int32_t status = 0;
auto allianceStationID = HAL_GetAllianceStation(&status);
switch (allianceStationID) {
@@ -466,7 +551,7 @@ DriverStation::Alliance DriverStation::GetAlliance() const {
}
}
int DriverStation::GetLocation() const {
int DriverStation::GetLocation() {
int32_t status = 0;
auto allianceStationID = HAL_GetAllianceStation(&status);
switch (allianceStationID) {
@@ -489,36 +574,37 @@ void DriverStation::WaitForData() {
}
bool DriverStation::WaitForData(units::second_t timeout) {
auto& inst = ::GetInstance();
auto timeoutTime = std::chrono::steady_clock::now() +
std::chrono::steady_clock::duration{timeout};
std::unique_lock lock(m_waitForDataMutex);
std::unique_lock lock(inst.waitForDataMutex);
int& lastCount = GetDSLastCount();
int currentCount = m_waitForDataCounter;
int currentCount = inst.waitForDataCounter;
if (lastCount != currentCount) {
lastCount = currentCount;
return true;
}
while (m_waitForDataCounter == currentCount) {
while (inst.waitForDataCounter == currentCount) {
if (timeout > 0_s) {
auto timedOut = m_waitForDataCond.wait_until(lock, timeoutTime);
auto timedOut = inst.waitForDataCond.wait_until(lock, timeoutTime);
if (timedOut == std::cv_status::timeout) {
return false;
}
} else {
m_waitForDataCond.wait(lock);
inst.waitForDataCond.wait(lock);
}
}
lastCount = m_waitForDataCounter;
lastCount = inst.waitForDataCounter;
return true;
}
double DriverStation::GetMatchTime() const {
double DriverStation::GetMatchTime() {
int32_t status = 0;
return HAL_GetMatchTime(&status);
}
double DriverStation::GetBatteryVoltage() const {
double DriverStation::GetBatteryVoltage() {
int32_t status = 0;
double voltage = HAL_GetVinVoltage(&status);
FRC_CheckErrorStatus(status, "{}", "getVinVoltage");
@@ -526,92 +612,101 @@ double DriverStation::GetBatteryVoltage() const {
return voltage;
}
void DriverStation::WakeupWaitForData() {
std::scoped_lock waitLock(m_waitForDataMutex);
// Nofify all threads
m_waitForDataCounter++;
m_waitForDataCond.notify_all();
void DriverStation::InDisabled(bool entering) {
::GetInstance().userInDisabled = entering;
}
void DriverStation::GetData() {
void DriverStation::InAutonomous(bool entering) {
::GetInstance().userInAutonomous = entering;
}
void DriverStation::InOperatorControl(bool entering) {
::GetInstance().userInTeleop = entering;
}
void DriverStation::InTest(bool entering) {
::GetInstance().userInTest = entering;
}
void DriverStation::WakeupWaitForData() {
auto& inst = ::GetInstance();
std::scoped_lock waitLock(inst.waitForDataMutex);
// Nofify all threads
inst.waitForDataCounter++;
inst.waitForDataCond.notify_all();
}
/**
* Copy data from the DS task for the user.
*
* If no new data exists, it will just be returned, otherwise
* the data will be copied from the DS polling loop.
*/
void GetData() {
auto& inst = ::GetInstance();
{
// Compute the pressed and released buttons
HAL_JoystickButtons currentButtons;
std::unique_lock lock(m_buttonEdgeMutex);
std::unique_lock lock(inst.buttonEdgeMutex);
for (int32_t i = 0; i < kJoystickPorts; i++) {
for (int32_t i = 0; i < DriverStation::kJoystickPorts; i++) {
HAL_GetJoystickButtons(i, &currentButtons);
// If buttons weren't pressed and are now, set flags in m_buttonsPressed
m_joystickButtonsPressed[i] |=
~m_previousButtonStates[i].buttons & currentButtons.buttons;
inst.joystickButtonsPressed[i] |=
~inst.previousButtonStates[i].buttons & currentButtons.buttons;
// If buttons were pressed and aren't now, set flags in m_buttonsReleased
m_joystickButtonsReleased[i] |=
m_previousButtonStates[i].buttons & ~currentButtons.buttons;
inst.joystickButtonsReleased[i] |=
inst.previousButtonStates[i].buttons & ~currentButtons.buttons;
m_previousButtonStates[i] = currentButtons;
inst.previousButtonStates[i] = currentButtons;
}
}
WakeupWaitForData();
DriverStation::WakeupWaitForData();
SendMatchData();
}
void DriverStation::SilenceJoystickConnectionWarning(bool silence) {
m_silenceJoystickWarning = silence;
::GetInstance().silenceJoystickWarning = silence;
}
bool DriverStation::IsJoystickConnectionWarningSilenced() const {
return !IsFMSAttached() && m_silenceJoystickWarning;
bool DriverStation::IsJoystickConnectionWarningSilenced() {
return !IsFMSAttached() && ::GetInstance().silenceJoystickWarning;
}
DriverStation::DriverStation() {
HAL_Initialize(500, 0);
m_waitForDataCounter = 0;
m_matchDataSender = std::make_unique<MatchDataSender>();
// All joysticks should default to having zero axes, povs and buttons, so
// uninitialized memory doesn't get sent to speed controllers.
for (unsigned int i = 0; i < kJoystickPorts; i++) {
m_joystickButtonsPressed[i] = 0;
m_joystickButtonsReleased[i] = 0;
m_previousButtonStates[i].count = 0;
m_previousButtonStates[i].buttons = 0;
}
m_dsThread = std::thread(&DriverStation::Run, this);
}
void DriverStation::ReportJoystickUnpluggedErrorV(fmt::string_view format,
fmt::format_args args) {
void ReportJoystickUnpluggedErrorV(fmt::string_view format,
fmt::format_args args) {
auto& inst = GetInstance();
auto currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
if (currentTime > inst.nextMessageTime) {
ReportErrorV(err::Error, "", 0, "", format, args);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
inst.nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
}
}
void DriverStation::ReportJoystickUnpluggedWarningV(fmt::string_view format,
fmt::format_args args) {
if (IsFMSAttached() || !m_silenceJoystickWarning) {
void ReportJoystickUnpluggedWarningV(fmt::string_view format,
fmt::format_args args) {
auto& inst = GetInstance();
if (DriverStation::IsFMSAttached() || !inst.silenceJoystickWarning) {
auto currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
if (currentTime > inst.nextMessageTime) {
ReportErrorV(warn::Warning, "", 0, "", format, args);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
inst.nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
}
}
}
void DriverStation::Run() {
m_isRunning = true;
void Run() {
auto& inst = GetInstance();
inst.isRunning = true;
int safetyCounter = 0;
while (m_isRunning) {
while (inst.isRunning) {
HAL_WaitForDSData();
GetData();
if (IsDisabled()) {
if (DriverStation::IsDisabled()) {
safetyCounter = 0;
}
@@ -619,22 +714,22 @@ void DriverStation::Run() {
MotorSafety::CheckMotors();
safetyCounter = 0;
}
if (m_userInDisabled) {
if (inst.userInDisabled) {
HAL_ObserveUserProgramDisabled();
}
if (m_userInAutonomous) {
if (inst.userInAutonomous) {
HAL_ObserveUserProgramAutonomous();
}
if (m_userInTeleop) {
if (inst.userInTeleop) {
HAL_ObserveUserProgramTeleop();
}
if (m_userInTest) {
if (inst.userInTest) {
HAL_ObserveUserProgramTest();
}
}
}
void DriverStation::SendMatchData() {
void SendMatchData() {
int32_t status = 0;
HAL_AllianceStationID alliance = HAL_GetAllianceStation(&status);
bool isRedAlliance = false;
@@ -669,19 +764,20 @@ void DriverStation::SendMatchData() {
HAL_MatchInfo tmpDataStore;
HAL_GetMatchInfo(&tmpDataStore);
m_matchDataSender->alliance.Set(isRedAlliance);
m_matchDataSender->station.Set(stationNumber);
m_matchDataSender->eventName.Set(tmpDataStore.eventName);
m_matchDataSender->gameSpecificMessage.Set(
auto& inst = GetInstance();
inst.matchDataSender.alliance.Set(isRedAlliance);
inst.matchDataSender.station.Set(stationNumber);
inst.matchDataSender.eventName.Set(tmpDataStore.eventName);
inst.matchDataSender.gameSpecificMessage.Set(
std::string(reinterpret_cast<char*>(tmpDataStore.gameSpecificMessage),
tmpDataStore.gameSpecificMessageSize));
m_matchDataSender->matchNumber.Set(tmpDataStore.matchNumber);
m_matchDataSender->replayNumber.Set(tmpDataStore.replayNumber);
m_matchDataSender->matchType.Set(static_cast<int>(tmpDataStore.matchType));
inst.matchDataSender.matchNumber.Set(tmpDataStore.matchNumber);
inst.matchDataSender.replayNumber.Set(tmpDataStore.replayNumber);
inst.matchDataSender.matchType.Set(static_cast<int>(tmpDataStore.matchType));
HAL_ControlWord ctlWord;
HAL_GetControlWord(&ctlWord);
int32_t wordInt = 0;
std::memcpy(&wordInt, &ctlWord, sizeof(wordInt));
m_matchDataSender->controlWord.Set(wordInt);
inst.matchDataSender.controlWord.Set(wordInt);
}

View File

@@ -49,7 +49,7 @@ void DutyCycle::InitDutyCycle() {
FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel());
int index = GetFPGAIndex();
HAL_Report(HALUsageReporting::kResourceType_DutyCycle, index + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "Duty Cycle", index);
wpi::SendableRegistry::AddLW(this, "Duty Cycle", index);
}
int DutyCycle::GetFPGAIndex() const {

View File

@@ -72,8 +72,8 @@ void DutyCycleEncoder::Init() {
m_analogTrigger->CreateOutput(AnalogTriggerType::kFallingPulse));
}
wpi::SendableRegistry::GetInstance().AddLW(this, "DutyCycle Encoder",
m_dutyCycle->GetSourceChannel());
wpi::SendableRegistry::AddLW(this, "DutyCycle Encoder",
m_dutyCycle->GetSourceChannel());
}
units::turn_t DutyCycleEncoder::Get() const {

View File

@@ -22,9 +22,8 @@ Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection,
m_aSource = std::make_shared<DigitalInput>(aChannel);
m_bSource = std::make_shared<DigitalInput>(bChannel);
InitEncoder(reverseDirection, encodingType);
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddChild(this, m_aSource.get());
registry.AddChild(this, m_bSource.get());
wpi::SendableRegistry::AddChild(this, m_aSource.get());
wpi::SendableRegistry::AddChild(this, m_bSource.get());
}
Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource,
@@ -181,7 +180,7 @@ int Encoder::GetSamplesToAverage() const {
void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) {
// Force digital input if just given an index
m_indexSource = std::make_shared<DigitalInput>(channel);
wpi::SendableRegistry::GetInstance().AddChild(this, m_indexSource.get());
wpi::SendableRegistry::AddChild(this, m_indexSource.get());
SetIndexSource(*m_indexSource.get(), type);
}
@@ -240,8 +239,7 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex() + 1,
encodingType);
wpi::SendableRegistry::GetInstance().AddLW(this, "Encoder",
m_aSource->GetChannel());
wpi::SendableRegistry::AddLW(this, "Encoder", m_aSource->GetChannel());
}
double Encoder::DecodingScaleFactor() const {

View File

@@ -11,7 +11,7 @@
using namespace frc;
GenericHID::GenericHID(int port) : m_ds(&DriverStation::GetInstance()) {
GenericHID::GenericHID(int port) {
if (port < 0 || port >= DriverStation::kJoystickPorts) {
throw FRC_MakeError(warn::BadJoystickIndex, "port {} out of range", port);
}
@@ -19,51 +19,51 @@ GenericHID::GenericHID(int port) : m_ds(&DriverStation::GetInstance()) {
}
bool GenericHID::GetRawButton(int button) const {
return m_ds->GetStickButton(m_port, button);
return DriverStation::GetStickButton(m_port, button);
}
bool GenericHID::GetRawButtonPressed(int button) {
return m_ds->GetStickButtonPressed(m_port, button);
return DriverStation::GetStickButtonPressed(m_port, button);
}
bool GenericHID::GetRawButtonReleased(int button) {
return m_ds->GetStickButtonReleased(m_port, button);
return DriverStation::GetStickButtonReleased(m_port, button);
}
double GenericHID::GetRawAxis(int axis) const {
return m_ds->GetStickAxis(m_port, axis);
return DriverStation::GetStickAxis(m_port, axis);
}
int GenericHID::GetPOV(int pov) const {
return m_ds->GetStickPOV(m_port, pov);
return DriverStation::GetStickPOV(m_port, pov);
}
int GenericHID::GetAxisCount() const {
return m_ds->GetStickAxisCount(m_port);
return DriverStation::GetStickAxisCount(m_port);
}
int GenericHID::GetPOVCount() const {
return m_ds->GetStickPOVCount(m_port);
return DriverStation::GetStickPOVCount(m_port);
}
int GenericHID::GetButtonCount() const {
return m_ds->GetStickButtonCount(m_port);
return DriverStation::GetStickButtonCount(m_port);
}
bool GenericHID::IsConnected() const {
return m_ds->IsJoystickConnected(m_port);
return DriverStation::IsJoystickConnected(m_port);
}
GenericHID::HIDType GenericHID::GetType() const {
return static_cast<HIDType>(m_ds->GetJoystickType(m_port));
return static_cast<HIDType>(DriverStation::GetJoystickType(m_port));
}
std::string GenericHID::GetName() const {
return m_ds->GetJoystickName(m_port);
return DriverStation::GetJoystickName(m_port);
}
int GenericHID::GetAxisType(int axis) const {
return m_ds->GetJoystickAxisType(m_port, axis);
return DriverStation::GetJoystickAxisType(m_port, axis);
}
int GenericHID::GetPort() const {

View File

@@ -110,7 +110,7 @@ void IterativeRobotBase::LoopFunc() {
// Call DisabledInit() if we are now just entering disabled mode from
// either a different mode or from power-on.
if (m_lastMode != Mode::kDisabled) {
LiveWindow::GetInstance()->SetEnabled(false);
LiveWindow::SetEnabled(false);
Shuffleboard::DisableActuatorWidgets();
DisabledInit();
m_watchdog.AddEpoch("DisabledInit()");
@@ -124,7 +124,7 @@ void IterativeRobotBase::LoopFunc() {
// Call AutonomousInit() if we are now just entering autonomous mode from
// either a different mode or from power-on.
if (m_lastMode != Mode::kAutonomous) {
LiveWindow::GetInstance()->SetEnabled(false);
LiveWindow::SetEnabled(false);
Shuffleboard::DisableActuatorWidgets();
AutonomousInit();
m_watchdog.AddEpoch("AutonomousInit()");
@@ -138,7 +138,7 @@ void IterativeRobotBase::LoopFunc() {
// Call TeleopInit() if we are now just entering teleop mode from
// either a different mode or from power-on.
if (m_lastMode != Mode::kTeleop) {
LiveWindow::GetInstance()->SetEnabled(false);
LiveWindow::SetEnabled(false);
Shuffleboard::DisableActuatorWidgets();
TeleopInit();
m_watchdog.AddEpoch("TeleopInit()");
@@ -152,7 +152,7 @@ void IterativeRobotBase::LoopFunc() {
// Call TestInit() if we are now just entering test mode from
// either a different mode or from power-on.
if (m_lastMode != Mode::kTest) {
LiveWindow::GetInstance()->SetEnabled(true);
LiveWindow::SetEnabled(true);
Shuffleboard::EnableActuatorWidgets();
TestInit();
m_watchdog.AddEpoch("TestInit()");
@@ -169,7 +169,7 @@ void IterativeRobotBase::LoopFunc() {
SmartDashboard::UpdateValues();
m_watchdog.AddEpoch("SmartDashboard::UpdateValues()");
LiveWindow::GetInstance()->UpdateValues();
LiveWindow::UpdateValues();
m_watchdog.AddEpoch("LiveWindow::UpdateValues()");
Shuffleboard::Update();
m_watchdog.AddEpoch("Shuffleboard::Update()");

View File

@@ -82,8 +82,7 @@ void MotorSafety::Check() {
stopTime = m_stopTime;
}
DriverStation& ds = DriverStation::GetInstance();
if (!enabled || ds.IsDisabled() || ds.IsTest()) {
if (!enabled || DriverStation::IsDisabled() || DriverStation::IsTest()) {
return;
}

View File

@@ -40,7 +40,7 @@ PWM::PWM(int channel, bool registerSendable) {
HAL_Report(HALUsageReporting::kResourceType_PWM, channel + 1);
if (registerSendable) {
wpi::SendableRegistry::GetInstance().AddLW(this, "PWM", channel);
wpi::SendableRegistry::AddLW(this, "PWM", channel);
}
}

View File

@@ -24,8 +24,7 @@ PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) {
FRC_CheckErrorStatus(status, "Module {}", module);
HAL_Report(HALUsageReporting::kResourceType_PDP, module + 1);
wpi::SendableRegistry::GetInstance().AddLW(this, "PowerDistributionPanel",
module);
wpi::SendableRegistry::AddLW(this, "PowerDistributionPanel", module);
}
double PowerDistributionPanel::GetVoltage() const {

View File

@@ -7,6 +7,7 @@
#include <algorithm>
#include <hal/FRCUsageReporting.h>
#include <networktables/NetworkTable.h>
#include <networktables/NetworkTableInstance.h>
using namespace frc;
@@ -14,42 +15,59 @@ using namespace frc;
// The Preferences table name
static constexpr std::string_view kTableName{"Preferences"};
namespace {
struct Instance {
Instance();
std::shared_ptr<nt::NetworkTable> table{
nt::NetworkTableInstance::GetDefault().GetTable(kTableName)};
NT_EntryListener listener;
};
} // namespace
static Instance& GetInstance() {
static Instance instance;
return instance;
}
Preferences* Preferences::GetInstance() {
::GetInstance();
static Preferences instance;
return &instance;
}
std::vector<std::string> Preferences::GetKeys() {
return m_table->GetKeys();
return ::GetInstance().table->GetKeys();
}
std::string Preferences::GetString(std::string_view key,
std::string_view defaultValue) {
return m_table->GetString(key, defaultValue);
return ::GetInstance().table->GetString(key, defaultValue);
}
int Preferences::GetInt(std::string_view key, int defaultValue) {
return static_cast<int>(m_table->GetNumber(key, defaultValue));
return static_cast<int>(::GetInstance().table->GetNumber(key, defaultValue));
}
double Preferences::GetDouble(std::string_view key, double defaultValue) {
return m_table->GetNumber(key, defaultValue);
return ::GetInstance().table->GetNumber(key, defaultValue);
}
float Preferences::GetFloat(std::string_view key, float defaultValue) {
return m_table->GetNumber(key, defaultValue);
return ::GetInstance().table->GetNumber(key, defaultValue);
}
bool Preferences::GetBoolean(std::string_view key, bool defaultValue) {
return m_table->GetBoolean(key, defaultValue);
return ::GetInstance().table->GetBoolean(key, defaultValue);
}
int64_t Preferences::GetLong(std::string_view key, int64_t defaultValue) {
return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
return static_cast<int64_t>(
::GetInstance().table->GetNumber(key, defaultValue));
}
void Preferences::SetString(std::string_view key, std::string_view value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetString(value);
entry.SetPersistent();
}
@@ -59,12 +77,12 @@ void Preferences::PutString(std::string_view key, std::string_view value) {
}
void Preferences::InitString(std::string_view key, std::string_view value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultString(value);
}
void Preferences::SetInt(std::string_view key, int value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
@@ -74,12 +92,12 @@ void Preferences::PutInt(std::string_view key, int value) {
}
void Preferences::InitInt(std::string_view key, int value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
}
void Preferences::SetDouble(std::string_view key, double value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
@@ -89,12 +107,12 @@ void Preferences::PutDouble(std::string_view key, double value) {
}
void Preferences::InitDouble(std::string_view key, double value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
}
void Preferences::SetFloat(std::string_view key, float value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
@@ -104,12 +122,12 @@ void Preferences::PutFloat(std::string_view key, float value) {
}
void Preferences::InitFloat(std::string_view key, float value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
}
void Preferences::SetBoolean(std::string_view key, bool value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetBoolean(value);
entry.SetPersistent();
}
@@ -119,12 +137,12 @@ void Preferences::PutBoolean(std::string_view key, bool value) {
}
void Preferences::InitBoolean(std::string_view key, bool value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultBoolean(value);
}
void Preferences::SetLong(std::string_view key, int64_t value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDouble(value);
entry.SetPersistent();
}
@@ -134,16 +152,16 @@ void Preferences::PutLong(std::string_view key, int64_t value) {
}
void Preferences::InitLong(std::string_view key, int64_t value) {
auto entry = m_table->GetEntry(key);
auto entry = ::GetInstance().table->GetEntry(key);
entry.SetDefaultDouble(value);
}
bool Preferences::ContainsKey(std::string_view key) {
return m_table->ContainsKey(key);
return ::GetInstance().table->ContainsKey(key);
}
void Preferences::Remove(std::string_view key) {
m_table->Delete(key);
::GetInstance().table->Delete(key);
}
void Preferences::RemoveAll() {
@@ -154,10 +172,9 @@ void Preferences::RemoveAll() {
}
}
Preferences::Preferences()
: m_table(nt::NetworkTableInstance::GetDefault().GetTable(kTableName)) {
m_table->GetEntry(".type").SetString("RobotPreferences");
m_listener = m_table->AddEntryListener(
Instance::Instance() {
table->GetEntry(".type").SetString("RobotPreferences");
listener = table->AddEntryListener(
[=](nt::NetworkTable* table, std::string_view name,
nt::NetworkTableEntry entry, std::shared_ptr<nt::Value> value,
int flags) { entry.SetPersistent(); },

View File

@@ -56,7 +56,7 @@ Relay::Relay(int channel, Relay::Direction direction)
FRC_CheckErrorStatus(status, "Channel {}", m_channel);
}
wpi::SendableRegistry::GetInstance().AddLW(this, "Relay", m_channel);
wpi::SendableRegistry::AddLW(this, "Relay", m_channel);
}
Relay::~Relay() {

View File

@@ -9,25 +9,25 @@
using namespace frc;
bool RobotState::IsDisabled() {
return DriverStation::GetInstance().IsDisabled();
return DriverStation::IsDisabled();
}
bool RobotState::IsEnabled() {
return DriverStation::GetInstance().IsEnabled();
return DriverStation::IsEnabled();
}
bool RobotState::IsEStopped() {
return DriverStation::GetInstance().IsEStopped();
return DriverStation::IsEStopped();
}
bool RobotState::IsOperatorControl() {
return DriverStation::GetInstance().IsOperatorControl();
return DriverStation::IsOperatorControl();
}
bool RobotState::IsAutonomous() {
return DriverStation::GetInstance().IsAutonomous();
return DriverStation::IsAutonomous();
}
bool RobotState::IsTest() {
return DriverStation::GetInstance().IsTest();
return DriverStation::IsTest();
}

View File

@@ -24,7 +24,7 @@ Servo::Servo(int channel) : PWM(channel) {
SetPeriodMultiplier(kPeriodMultiplier_4X);
HAL_Report(HALUsageReporting::kResourceType_Servo, channel + 1);
wpi::SendableRegistry::GetInstance().SetName(this, "Servo", channel);
wpi::SendableRegistry::SetName(this, "Servo", channel);
}
void Servo::Set(double value) {

View File

@@ -36,8 +36,8 @@ Solenoid::Solenoid(std::shared_ptr<PneumaticsBase> module, int channel)
HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel + 1,
m_module->GetModuleNumber() + 1);
wpi::SendableRegistry::GetInstance().AddLW(
this, "Solenoid", m_module->GetModuleNumber(), m_channel);
wpi::SendableRegistry::AddLW(this, "Solenoid", m_module->GetModuleNumber(),
m_channel);
}
Solenoid::~Solenoid() {}

View File

@@ -20,12 +20,11 @@ SpeedControllerGroup::SpeedControllerGroup(
void SpeedControllerGroup::Initialize() {
for (auto& speedController : m_speedControllers) {
wpi::SendableRegistry::GetInstance().AddChild(this, &speedController.get());
wpi::SendableRegistry::AddChild(this, &speedController.get());
}
static int instances = 0;
++instances;
wpi::SendableRegistry::GetInstance().Add(this, "SpeedControllerGroup",
instances);
wpi::SendableRegistry::Add(this, "SpeedControllerGroup", instances);
}
void SpeedControllerGroup::Set(double speed) {

View File

@@ -30,9 +30,8 @@ Ultrasonic::Ultrasonic(int pingChannel, int echoChannel)
m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
m_counter(m_echoChannel) {
Initialize();
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddChild(this, m_pingChannel.get());
registry.AddChild(this, m_echoChannel.get());
wpi::SendableRegistry::AddChild(this, m_pingChannel.get());
wpi::SendableRegistry::AddChild(this, m_echoChannel.get());
}
Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel)
@@ -185,8 +184,7 @@ void Ultrasonic::Initialize() {
static int instances = 0;
instances++;
HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
wpi::SendableRegistry::GetInstance().AddLW(this, "Ultrasonic",
m_echoChannel->GetChannel());
wpi::SendableRegistry::AddLW(this, "Ultrasonic", m_echoChannel->GetChannel());
}
void Ultrasonic::UltrasonicChecker() {

View File

@@ -31,7 +31,7 @@ PIDController::PIDController(double Kp, double Ki, double Kd,
static int instances = 0;
instances++;
HAL_Report(HALUsageReporting::kResourceType_PIDController2, instances);
wpi::SendableRegistry::GetInstance().Add(this, "PIDController", instances);
wpi::SendableRegistry::Add(this, "PIDController", instances);
}
void PIDController::SetPID(double Kp, double Ki, double Kd) {

View File

@@ -26,12 +26,11 @@ using namespace frc;
DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
SpeedController& rightMotor)
: m_leftMotor(&leftMotor), m_rightMotor(&rightMotor) {
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddChild(this, m_leftMotor);
registry.AddChild(this, m_rightMotor);
wpi::SendableRegistry::AddChild(this, m_leftMotor);
wpi::SendableRegistry::AddChild(this, m_rightMotor);
static int instances = 0;
++instances;
registry.AddLW(this, "DifferentialDrive", instances);
wpi::SendableRegistry::AddLW(this, "DifferentialDrive", instances);
}
void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,

View File

@@ -43,13 +43,12 @@ KilloughDrive::KilloughDrive(SpeedController& leftMotor,
std::sin(rightMotorAngle * (wpi::numbers::pi / 180.0))};
m_backVec = {std::cos(backMotorAngle * (wpi::numbers::pi / 180.0)),
std::sin(backMotorAngle * (wpi::numbers::pi / 180.0))};
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddChild(this, m_leftMotor);
registry.AddChild(this, m_rightMotor);
registry.AddChild(this, m_backMotor);
wpi::SendableRegistry::AddChild(this, m_leftMotor);
wpi::SendableRegistry::AddChild(this, m_rightMotor);
wpi::SendableRegistry::AddChild(this, m_backMotor);
static int instances = 0;
++instances;
registry.AddLW(this, "KilloughDrive", instances);
wpi::SendableRegistry::AddLW(this, "KilloughDrive", instances);
}
void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,

View File

@@ -33,14 +33,13 @@ MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
m_rearLeftMotor(&rearLeftMotor),
m_frontRightMotor(&frontRightMotor),
m_rearRightMotor(&rearRightMotor) {
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddChild(this, m_frontLeftMotor);
registry.AddChild(this, m_rearLeftMotor);
registry.AddChild(this, m_frontRightMotor);
registry.AddChild(this, m_rearRightMotor);
wpi::SendableRegistry::AddChild(this, m_frontLeftMotor);
wpi::SendableRegistry::AddChild(this, m_rearLeftMotor);
wpi::SendableRegistry::AddChild(this, m_frontRightMotor);
wpi::SendableRegistry::AddChild(this, m_rearRightMotor);
static int instances = 0;
++instances;
registry.AddLW(this, "MecanumDrive", instances);
wpi::SendableRegistry::AddLW(this, "MecanumDrive", instances);
}
void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,

View File

@@ -15,133 +15,152 @@
using namespace frc;
struct LiveWindow::Impl {
Impl();
namespace {
struct Component {
bool firstTime = true;
bool telemetryEnabled = true;
};
struct Component {
bool firstTime = true;
bool telemetryEnabled = true;
};
struct Instance {
Instance() {
wpi::SendableRegistry::SetLiveWindowBuilderFactory(
[] { return std::make_unique<SendableBuilderImpl>(); });
}
wpi::mutex mutex;
wpi::SendableRegistry& registry;
int dataHandle;
int dataHandle = wpi::SendableRegistry::GetDataHandle();
std::shared_ptr<nt::NetworkTable> liveWindowTable;
std::shared_ptr<nt::NetworkTable> statusTable;
nt::NetworkTableEntry enabledEntry;
std::shared_ptr<nt::NetworkTable> liveWindowTable =
nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow");
std::shared_ptr<nt::NetworkTable> statusTable =
liveWindowTable->GetSubTable(".status");
nt::NetworkTableEntry enabledEntry = statusTable->GetEntry("LW Enabled");
bool startLiveWindow = false;
bool liveWindowEnabled = false;
bool telemetryEnabled = true;
std::function<void()> enabled;
std::function<void()> disabled;
std::shared_ptr<Component> GetOrAdd(wpi::Sendable* sendable);
};
} // namespace
LiveWindow::Impl::Impl()
: registry(wpi::SendableRegistry::GetInstance()),
dataHandle(registry.GetDataHandle()),
liveWindowTable(
nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow")) {
registry.SetLiveWindowBuilderFactory(
[] { return std::make_unique<SendableBuilderImpl>(); });
statusTable = liveWindowTable->GetSubTable(".status");
enabledEntry = statusTable->GetEntry("LW Enabled");
static Instance& GetInstance() {
static Instance instance;
return instance;
}
std::shared_ptr<LiveWindow::Impl::Component> LiveWindow::Impl::GetOrAdd(
wpi::Sendable* sendable) {
std::shared_ptr<Component> Instance::GetOrAdd(wpi::Sendable* sendable) {
auto data = std::static_pointer_cast<Component>(
registry.GetData(sendable, dataHandle));
wpi::SendableRegistry::GetData(sendable, dataHandle));
if (!data) {
data = std::make_shared<Component>();
registry.SetData(sendable, dataHandle, data);
wpi::SendableRegistry::SetData(sendable, dataHandle, data);
}
return data;
}
LiveWindow* LiveWindow::GetInstance() {
::GetInstance();
static LiveWindow instance;
return &instance;
}
void LiveWindow::SetEnabledCallback(std::function<void()> func) {
::GetInstance().enabled = func;
}
void LiveWindow::SetDisabledCallback(std::function<void()> func) {
::GetInstance().disabled = func;
}
void LiveWindow::EnableTelemetry(wpi::Sendable* sendable) {
std::scoped_lock lock(m_impl->mutex);
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.mutex);
// Re-enable global setting in case DisableAllTelemetry() was called.
m_impl->telemetryEnabled = true;
m_impl->GetOrAdd(sendable)->telemetryEnabled = true;
inst.telemetryEnabled = true;
inst.GetOrAdd(sendable)->telemetryEnabled = true;
}
void LiveWindow::DisableTelemetry(wpi::Sendable* sendable) {
std::scoped_lock lock(m_impl->mutex);
m_impl->GetOrAdd(sendable)->telemetryEnabled = false;
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.mutex);
inst.GetOrAdd(sendable)->telemetryEnabled = false;
}
void LiveWindow::DisableAllTelemetry() {
std::scoped_lock lock(m_impl->mutex);
m_impl->telemetryEnabled = false;
m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.mutex);
inst.telemetryEnabled = false;
wpi::SendableRegistry::ForeachLiveWindow(inst.dataHandle, [&](auto& cbdata) {
if (!cbdata.data) {
cbdata.data = std::make_shared<Impl::Component>();
cbdata.data = std::make_shared<Component>();
}
std::static_pointer_cast<Impl::Component>(cbdata.data)->telemetryEnabled =
false;
std::static_pointer_cast<Component>(cbdata.data)->telemetryEnabled = false;
});
}
bool LiveWindow::IsEnabled() const {
std::scoped_lock lock(m_impl->mutex);
return m_impl->liveWindowEnabled;
bool LiveWindow::IsEnabled() {
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.mutex);
return inst.liveWindowEnabled;
}
void LiveWindow::SetEnabled(bool enabled) {
std::scoped_lock lock(m_impl->mutex);
if (m_impl->liveWindowEnabled == enabled) {
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.mutex);
if (inst.liveWindowEnabled == enabled) {
return;
}
m_impl->startLiveWindow = enabled;
m_impl->liveWindowEnabled = enabled;
inst.startLiveWindow = enabled;
inst.liveWindowEnabled = enabled;
// Force table generation now to make sure everything is defined
UpdateValuesUnsafe();
if (enabled) {
if (this->enabled) {
this->enabled();
if (inst.enabled) {
inst.enabled();
}
} else {
m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
static_cast<SendableBuilderImpl&>(cbdata.builder).StopLiveWindowMode();
});
if (this->disabled) {
this->disabled();
wpi::SendableRegistry::ForeachLiveWindow(
inst.dataHandle, [&](auto& cbdata) {
static_cast<SendableBuilderImpl&>(cbdata.builder)
.StopLiveWindowMode();
});
if (inst.disabled) {
inst.disabled();
}
}
m_impl->enabledEntry.SetBoolean(enabled);
inst.enabledEntry.SetBoolean(enabled);
}
void LiveWindow::UpdateValues() {
std::scoped_lock lock(m_impl->mutex);
auto& inst = ::GetInstance();
std::scoped_lock lock(inst.mutex);
UpdateValuesUnsafe();
}
void LiveWindow::UpdateValuesUnsafe() {
auto& inst = ::GetInstance();
// Only do this if either LiveWindow mode or telemetry is enabled.
if (!m_impl->liveWindowEnabled && !m_impl->telemetryEnabled) {
if (!inst.liveWindowEnabled && !inst.telemetryEnabled) {
return;
}
m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
wpi::SendableRegistry::ForeachLiveWindow(inst.dataHandle, [&](auto& cbdata) {
if (!cbdata.sendable || cbdata.parent) {
return;
}
if (!cbdata.data) {
cbdata.data = std::make_shared<Impl::Component>();
cbdata.data = std::make_shared<Component>();
}
auto& comp = *std::static_pointer_cast<Impl::Component>(cbdata.data);
auto& comp = *std::static_pointer_cast<Component>(cbdata.data);
if (!m_impl->liveWindowEnabled && !comp.telemetryEnabled) {
if (!inst.liveWindowEnabled && !comp.telemetryEnabled) {
return;
}
@@ -153,7 +172,7 @@ void LiveWindow::UpdateValuesUnsafe() {
if (cbdata.name.empty()) {
return;
}
auto ssTable = m_impl->liveWindowTable->GetSubTable(cbdata.subsystem);
auto ssTable = inst.liveWindowTable->GetSubTable(cbdata.subsystem);
std::shared_ptr<nt::NetworkTable> table;
// Treat name==subsystem as top level of subsystem
if (cbdata.name == cbdata.subsystem) {
@@ -169,13 +188,11 @@ void LiveWindow::UpdateValuesUnsafe() {
comp.firstTime = false;
}
if (m_impl->startLiveWindow) {
if (inst.startLiveWindow) {
static_cast<SendableBuilderImpl&>(cbdata.builder).StartLiveWindowMode();
}
cbdata.builder.Update();
});
m_impl->startLiveWindow = false;
inst.startLiveWindow = false;
}
LiveWindow::LiveWindow() : m_impl(new Impl) {}

View File

@@ -20,12 +20,11 @@ MotorControllerGroup::MotorControllerGroup(
void MotorControllerGroup::Initialize() {
for (auto& motorController : m_motorControllers) {
wpi::SendableRegistry::GetInstance().AddChild(this, &motorController.get());
wpi::SendableRegistry::AddChild(this, &motorController.get());
}
static int instances = 0;
++instances;
wpi::SendableRegistry::GetInstance().Add(this, "MotorControllerGroup",
instances);
wpi::SendableRegistry::Add(this, "MotorControllerGroup", instances);
}
void MotorControllerGroup::Set(double speed) {

View File

@@ -13,9 +13,8 @@ using namespace frc;
NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
: m_dio(dioChannel), m_pwm(pwmChannel) {
auto& registry = wpi::SendableRegistry::GetInstance();
registry.AddChild(this, &m_dio);
registry.AddChild(this, &m_pwm);
wpi::SendableRegistry::AddChild(this, &m_dio);
wpi::SendableRegistry::AddChild(this, &m_pwm);
SetExpiration(0_s);
SetSafetyEnabled(false);
@@ -24,7 +23,7 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
m_dio.EnablePWM(0.5);
HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel + 1);
registry.AddLW(this, "Nidec Brushless", pwmChannel);
wpi::SendableRegistry::AddLW(this, "Nidec Brushless", pwmChannel);
}
void NidecBrushless::Set(double speed) {

View File

@@ -44,7 +44,7 @@ int PWMMotorController::GetChannel() const {
PWMMotorController::PWMMotorController(std::string_view name, int channel)
: m_pwm(channel, false) {
wpi::SendableRegistry::GetInstance().AddLW(this, name, channel);
wpi::SendableRegistry::AddLW(this, name, channel);
}
void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) {

View File

@@ -21,7 +21,7 @@ std::shared_ptr<SendableCameraWrapper>& GetSendableCameraWrapper(
}
void AddToSendableRegistry(wpi::Sendable* sendable, std::string name) {
wpi::SendableRegistry::GetInstance().Add(sendable, name);
wpi::SendableRegistry::Add(sendable, name);
}
} // namespace detail

View File

@@ -67,7 +67,7 @@ ComplexWidget& ShuffleboardContainer::Add(std::string_view title,
}
ComplexWidget& ShuffleboardContainer::Add(wpi::Sendable& sendable) {
auto name = wpi::SendableRegistry::GetInstance().GetName(&sendable);
auto name = wpi::SendableRegistry::GetName(&sendable);
if (name.empty()) {
FRC_ReportError(err::Error, "{}", "Sendable must have a name");
}

View File

@@ -155,7 +155,7 @@ void DriverStationSim::SetMatchTime(double matchTime) {
void DriverStationSim::NotifyNewData() {
HALSIM_NotifyDriverStationNewData();
DriverStation::GetInstance().WaitForData();
DriverStation::WaitForData();
}
void DriverStationSim::SetSendError(bool shouldSend) {

View File

@@ -13,7 +13,7 @@ Field2d::Field2d() {
m_objects.emplace_back(
std::make_unique<FieldObject2d>("Robot", FieldObject2d::private_init{}));
m_objects[0]->SetPose(Pose2d{});
wpi::SendableRegistry::GetInstance().Add(this, "Field");
wpi::SendableRegistry::Add(this, "Field");
}
Field2d::Field2d(Field2d&& rhs) : SendableHelper(std::move(rhs)) {

View File

@@ -11,7 +11,7 @@ using namespace frc;
std::atomic_int SendableChooserBase::s_instances{0};
SendableChooserBase::SendableChooserBase() : m_instance{s_instances++} {
wpi::SendableRegistry::GetInstance().Add(this, "SendableChooser", m_instance);
wpi::SendableRegistry::Add(this, "SendableChooser", m_instance);
}
SendableChooserBase::SendableChooserBase(SendableChooserBase&& oth)

View File

@@ -12,95 +12,86 @@
#include <wpi/sendable/SendableRegistry.h>
#include "frc/Errors.h"
#include "frc/smartdashboard/ListenerExecutor.h"
#include "frc/smartdashboard/SendableBuilderImpl.h"
using namespace frc;
namespace {
class Singleton {
public:
static Singleton& GetInstance();
std::shared_ptr<nt::NetworkTable> table;
struct Instance {
detail::ListenerExecutor listenerExecutor;
std::shared_ptr<nt::NetworkTable> table =
nt::NetworkTableInstance::GetDefault().GetTable("SmartDashboard");
wpi::StringMap<wpi::SendableRegistry::UID> tablesToData;
wpi::mutex tablesToDataMutex;
private:
Singleton() {
table = nt::NetworkTableInstance::GetDefault().GetTable("SmartDashboard");
HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, 0);
}
Singleton(const Singleton&) = delete;
Singleton& operator=(const Singleton&) = delete;
};
} // namespace
Singleton& Singleton::GetInstance() {
static Singleton instance;
static Instance& GetInstance() {
HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, 0);
static Instance instance;
return instance;
}
void SmartDashboard::init() {
Singleton::GetInstance();
GetInstance();
}
bool SmartDashboard::ContainsKey(std::string_view key) {
return Singleton::GetInstance().table->ContainsKey(key);
return GetInstance().table->ContainsKey(key);
}
std::vector<std::string> SmartDashboard::GetKeys(int types) {
return Singleton::GetInstance().table->GetKeys(types);
return GetInstance().table->GetKeys(types);
}
void SmartDashboard::SetPersistent(std::string_view key) {
Singleton::GetInstance().table->GetEntry(key).SetPersistent();
GetInstance().table->GetEntry(key).SetPersistent();
}
void SmartDashboard::ClearPersistent(std::string_view key) {
Singleton::GetInstance().table->GetEntry(key).ClearPersistent();
GetInstance().table->GetEntry(key).ClearPersistent();
}
bool SmartDashboard::IsPersistent(std::string_view key) {
return Singleton::GetInstance().table->GetEntry(key).IsPersistent();
return GetInstance().table->GetEntry(key).IsPersistent();
}
void SmartDashboard::SetFlags(std::string_view key, unsigned int flags) {
Singleton::GetInstance().table->GetEntry(key).SetFlags(flags);
GetInstance().table->GetEntry(key).SetFlags(flags);
}
void SmartDashboard::ClearFlags(std::string_view key, unsigned int flags) {
Singleton::GetInstance().table->GetEntry(key).ClearFlags(flags);
GetInstance().table->GetEntry(key).ClearFlags(flags);
}
unsigned int SmartDashboard::GetFlags(std::string_view key) {
return Singleton::GetInstance().table->GetEntry(key).GetFlags();
return GetInstance().table->GetEntry(key).GetFlags();
}
void SmartDashboard::Delete(std::string_view key) {
Singleton::GetInstance().table->Delete(key);
GetInstance().table->Delete(key);
}
nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) {
return Singleton::GetInstance().table->GetEntry(key);
return GetInstance().table->GetEntry(key);
}
void SmartDashboard::PutData(std::string_view key, wpi::Sendable* data) {
if (!data) {
throw FRC_MakeError(err::NullParameter, "{}", "value");
}
auto& inst = Singleton::GetInstance();
auto& inst = GetInstance();
std::scoped_lock lock(inst.tablesToDataMutex);
auto& uid = inst.tablesToData[key];
auto& registry = wpi::SendableRegistry::GetInstance();
wpi::Sendable* sddata = registry.GetSendable(uid);
wpi::Sendable* sddata = wpi::SendableRegistry::GetSendable(uid);
if (sddata != data) {
uid = registry.GetUniqueId(data);
uid = wpi::SendableRegistry::GetUniqueId(data);
auto dataTable = inst.table->GetSubTable(key);
auto builder = std::make_unique<SendableBuilderImpl>();
auto builderPtr = builder.get();
builderPtr->SetTable(dataTable);
registry.Publish(uid, std::move(builder));
wpi::SendableRegistry::Publish(uid, std::move(builder));
builderPtr->StartListeners();
dataTable->GetEntry(".name").SetString(key);
}
@@ -110,163 +101,147 @@ void SmartDashboard::PutData(wpi::Sendable* value) {
if (!value) {
throw FRC_MakeError(err::NullParameter, "{}", "value");
}
auto name = wpi::SendableRegistry::GetInstance().GetName(value);
auto name = wpi::SendableRegistry::GetName(value);
if (!name.empty()) {
PutData(name, value);
}
}
wpi::Sendable* SmartDashboard::GetData(std::string_view key) {
auto& inst = Singleton::GetInstance();
auto& inst = GetInstance();
std::scoped_lock lock(inst.tablesToDataMutex);
auto it = inst.tablesToData.find(key);
if (it == inst.tablesToData.end()) {
throw FRC_MakeError(err::SmartDashboardMissingKey, "{}", key);
}
return wpi::SendableRegistry::GetInstance().GetSendable(it->getValue());
return wpi::SendableRegistry::GetSendable(it->getValue());
}
bool SmartDashboard::PutBoolean(std::string_view keyName, bool value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetBoolean(value);
return GetInstance().table->GetEntry(keyName).SetBoolean(value);
}
bool SmartDashboard::SetDefaultBoolean(std::string_view key,
bool defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultBoolean(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultBoolean(defaultValue);
}
bool SmartDashboard::GetBoolean(std::string_view keyName, bool defaultValue) {
return Singleton::GetInstance().table->GetEntry(keyName).GetBoolean(
defaultValue);
return GetInstance().table->GetEntry(keyName).GetBoolean(defaultValue);
}
bool SmartDashboard::PutNumber(std::string_view keyName, double value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetDouble(value);
return GetInstance().table->GetEntry(keyName).SetDouble(value);
}
bool SmartDashboard::SetDefaultNumber(std::string_view key,
double defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultDouble(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultDouble(defaultValue);
}
double SmartDashboard::GetNumber(std::string_view keyName,
double defaultValue) {
return Singleton::GetInstance().table->GetEntry(keyName).GetDouble(
defaultValue);
return GetInstance().table->GetEntry(keyName).GetDouble(defaultValue);
}
bool SmartDashboard::PutString(std::string_view keyName,
std::string_view value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetString(value);
return GetInstance().table->GetEntry(keyName).SetString(value);
}
bool SmartDashboard::SetDefaultString(std::string_view key,
std::string_view defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultString(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultString(defaultValue);
}
std::string SmartDashboard::GetString(std::string_view keyName,
std::string_view defaultValue) {
return Singleton::GetInstance().table->GetEntry(keyName).GetString(
defaultValue);
return GetInstance().table->GetEntry(keyName).GetString(defaultValue);
}
bool SmartDashboard::PutBooleanArray(std::string_view key,
wpi::span<const int> value) {
return Singleton::GetInstance().table->GetEntry(key).SetBooleanArray(value);
return GetInstance().table->GetEntry(key).SetBooleanArray(value);
}
bool SmartDashboard::SetDefaultBooleanArray(std::string_view key,
wpi::span<const int> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
return GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
defaultValue);
}
std::vector<int> SmartDashboard::GetBooleanArray(
std::string_view key, wpi::span<const int> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetBooleanArray(
defaultValue);
return GetInstance().table->GetEntry(key).GetBooleanArray(defaultValue);
}
bool SmartDashboard::PutNumberArray(std::string_view key,
wpi::span<const double> value) {
return Singleton::GetInstance().table->GetEntry(key).SetDoubleArray(value);
return GetInstance().table->GetEntry(key).SetDoubleArray(value);
}
bool SmartDashboard::SetDefaultNumberArray(
std::string_view key, wpi::span<const double> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultDoubleArray(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultDoubleArray(defaultValue);
}
std::vector<double> SmartDashboard::GetNumberArray(
std::string_view key, wpi::span<const double> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetDoubleArray(
defaultValue);
return GetInstance().table->GetEntry(key).GetDoubleArray(defaultValue);
}
bool SmartDashboard::PutStringArray(std::string_view key,
wpi::span<const std::string> value) {
return Singleton::GetInstance().table->GetEntry(key).SetStringArray(value);
return GetInstance().table->GetEntry(key).SetStringArray(value);
}
bool SmartDashboard::SetDefaultStringArray(
std::string_view key, wpi::span<const std::string> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultStringArray(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultStringArray(defaultValue);
}
std::vector<std::string> SmartDashboard::GetStringArray(
std::string_view key, wpi::span<const std::string> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetStringArray(
defaultValue);
return GetInstance().table->GetEntry(key).GetStringArray(defaultValue);
}
bool SmartDashboard::PutRaw(std::string_view key, std::string_view value) {
return Singleton::GetInstance().table->GetEntry(key).SetRaw(value);
return GetInstance().table->GetEntry(key).SetRaw(value);
}
bool SmartDashboard::SetDefaultRaw(std::string_view key,
std::string_view defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultRaw(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultRaw(defaultValue);
}
std::string SmartDashboard::GetRaw(std::string_view key,
std::string_view defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).GetRaw(defaultValue);
return GetInstance().table->GetEntry(key).GetRaw(defaultValue);
}
bool SmartDashboard::PutValue(std::string_view keyName,
std::shared_ptr<nt::Value> value) {
return Singleton::GetInstance().table->GetEntry(keyName).SetValue(value);
return GetInstance().table->GetEntry(keyName).SetValue(value);
}
bool SmartDashboard::SetDefaultValue(std::string_view key,
std::shared_ptr<nt::Value> defaultValue) {
return Singleton::GetInstance().table->GetEntry(key).SetDefaultValue(
defaultValue);
return GetInstance().table->GetEntry(key).SetDefaultValue(defaultValue);
}
std::shared_ptr<nt::Value> SmartDashboard::GetValue(std::string_view keyName) {
return Singleton::GetInstance().table->GetEntry(keyName).GetValue();
return GetInstance().table->GetEntry(keyName).GetValue();
}
detail::ListenerExecutor SmartDashboard::listenerExecutor;
void SmartDashboard::PostListenerTask(std::function<void()> task) {
listenerExecutor.Execute(task);
GetInstance().listenerExecutor.Execute(task);
}
void SmartDashboard::UpdateValues() {
auto& registry = wpi::SendableRegistry::GetInstance();
auto& inst = Singleton::GetInstance();
listenerExecutor.RunListenerTasks();
auto& inst = GetInstance();
inst.listenerExecutor.RunListenerTasks();
std::scoped_lock lock(inst.tablesToDataMutex);
for (auto& i : inst.tablesToData) {
registry.Update(i.getValue());
wpi::SendableRegistry::Update(i.getValue());
}
}

View File

@@ -151,42 +151,42 @@ static void SetupMathShared() {
}
bool RobotBase::IsEnabled() const {
return m_ds.IsEnabled();
return DriverStation::IsEnabled();
}
bool RobotBase::IsDisabled() const {
return m_ds.IsDisabled();
return DriverStation::IsDisabled();
}
bool RobotBase::IsAutonomous() const {
return m_ds.IsAutonomous();
return DriverStation::IsAutonomous();
}
bool RobotBase::IsAutonomousEnabled() const {
return m_ds.IsAutonomousEnabled();
return DriverStation::IsAutonomousEnabled();
}
bool RobotBase::IsOperatorControl() const {
return m_ds.IsOperatorControl();
return DriverStation::IsOperatorControl();
}
bool RobotBase::IsOperatorControlEnabled() const {
return m_ds.IsOperatorControlEnabled();
return DriverStation::IsOperatorControlEnabled();
}
bool RobotBase::IsTest() const {
return m_ds.IsTest();
return DriverStation::IsTest();
}
bool RobotBase::IsNewDataAvailable() const {
return m_ds.IsNewControlData();
return DriverStation::IsNewControlData();
}
std::thread::id RobotBase::GetThreadId() {
return m_threadId;
}
RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
RobotBase::RobotBase() {
m_threadId = std::this_thread::get_id();
SetupCameraServerShared();
@@ -219,14 +219,5 @@ RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
->GetEntry("LW Enabled")
.SetBoolean(false);
LiveWindow::GetInstance()->SetEnabled(false);
}
RobotBase::RobotBase(RobotBase&&) noexcept
: m_ds(DriverStation::GetInstance()) {}
RobotBase::~RobotBase() = default;
RobotBase& RobotBase::operator=(RobotBase&&) noexcept {
return *this;
LiveWindow::SetEnabled(false);
}

View File

@@ -4,24 +4,13 @@
#pragma once
#include <stdint.h>
#include <array>
#include <atomic>
#include <memory>
#include <string>
#include <thread>
#include <fmt/format.h>
#include <hal/DriverStationTypes.h>
#include <units/time.h>
#include <wpi/condition_variable.h>
#include <wpi/mutex.h>
#include <wpi/deprecated.h>
namespace frc {
class MatchDataSender;
/**
* Provide access to the network communication data to / from the Driver
* Station.
@@ -31,16 +20,13 @@ class DriverStation {
enum Alliance { kRed, kBlue, kInvalid };
enum MatchType { kNone, kPractice, kQualification, kElimination };
~DriverStation();
DriverStation(const DriverStation&) = delete;
DriverStation& operator=(const DriverStation&) = delete;
/**
* Return a reference to the singleton DriverStation.
*
* @return Reference to the DS instance
* @deprecated Use the static methods
*/
WPI_DEPRECATED("Use static methods")
static DriverStation& GetInstance();
static constexpr int kJoystickPorts = 6;
@@ -52,7 +38,7 @@ class DriverStation {
* @param button The button index, beginning at 1.
* @return The state of the joystick button.
*/
bool GetStickButton(int stick, int button);
static bool GetStickButton(int stick, int button);
/**
* Whether one joystick button was pressed since the last check. Button
@@ -62,7 +48,7 @@ class DriverStation {
* @param button The button index, beginning at 1.
* @return Whether the joystick button was pressed since the last check.
*/
bool GetStickButtonPressed(int stick, int button);
static bool GetStickButtonPressed(int stick, int button);
/**
* Whether one joystick button was released since the last check. Button
@@ -72,7 +58,7 @@ class DriverStation {
* @param button The button index, beginning at 1.
* @return Whether the joystick button was released since the last check.
*/
bool GetStickButtonReleased(int stick, int button);
static bool GetStickButtonReleased(int stick, int button);
/**
* Get the value of the axis on a joystick.
@@ -84,14 +70,14 @@ class DriverStation {
* @param axis The analog axis value to read from the joystick.
* @return The value of the axis on the joystick.
*/
double GetStickAxis(int stick, int axis);
static double GetStickAxis(int stick, int axis);
/**
* Get the state of a POV on the joystick.
*
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
*/
int GetStickPOV(int stick, int pov);
static int GetStickPOV(int stick, int pov);
/**
* The state of the buttons on the joystick.
@@ -99,7 +85,7 @@ class DriverStation {
* @param stick The joystick to read.
* @return The state of the buttons on the joystick.
*/
int GetStickButtons(int stick) const;
static int GetStickButtons(int stick);
/**
* Returns the number of axes on a given joystick port.
@@ -107,7 +93,7 @@ class DriverStation {
* @param stick The joystick port number
* @return The number of axes on the indicated joystick
*/
int GetStickAxisCount(int stick) const;
static int GetStickAxisCount(int stick);
/**
* Returns the number of POVs on a given joystick port.
@@ -115,7 +101,7 @@ class DriverStation {
* @param stick The joystick port number
* @return The number of POVs on the indicated joystick
*/
int GetStickPOVCount(int stick) const;
static int GetStickPOVCount(int stick);
/**
* Returns the number of buttons on a given joystick port.
@@ -123,7 +109,7 @@ class DriverStation {
* @param stick The joystick port number
* @return The number of buttons on the indicated joystick
*/
int GetStickButtonCount(int stick) const;
static int GetStickButtonCount(int stick);
/**
* Returns a boolean indicating if the controller is an xbox controller.
@@ -131,7 +117,7 @@ class DriverStation {
* @param stick The joystick port number
* @return A boolean that is true if the controller is an xbox controller.
*/
bool GetJoystickIsXbox(int stick) const;
static bool GetJoystickIsXbox(int stick);
/**
* Returns the type of joystick at a given port.
@@ -139,7 +125,7 @@ class DriverStation {
* @param stick The joystick port number
* @return The HID type of joystick at the given port
*/
int GetJoystickType(int stick) const;
static int GetJoystickType(int stick);
/**
* Returns the name of the joystick at the given port.
@@ -147,7 +133,7 @@ class DriverStation {
* @param stick The joystick port number
* @return The name of the joystick at the given port
*/
std::string GetJoystickName(int stick) const;
static std::string GetJoystickName(int stick);
/**
* Returns the types of Axes on a given joystick port.
@@ -155,7 +141,7 @@ class DriverStation {
* @param stick The joystick port number and the target axis
* @return What type of axis the axis is reporting to be
*/
int GetJoystickAxisType(int stick, int axis) const;
static int GetJoystickAxisType(int stick, int axis);
/**
* Returns if a joystick is connected to the Driver Station.
@@ -166,35 +152,35 @@ class DriverStation {
* @param stick The joystick port number
* @return true if a joystick is connected
*/
bool IsJoystickConnected(int stick) const;
static bool IsJoystickConnected(int stick);
/**
* Check if the DS has enabled the robot.
*
* @return True if the robot is enabled and the DS is connected
*/
bool IsEnabled() const;
static bool IsEnabled();
/**
* Check if the robot is disabled.
*
* @return True if the robot is explicitly disabled or the DS is not connected
*/
bool IsDisabled() const;
static bool IsDisabled();
/**
* Check if the robot is e-stopped.
*
* @return True if the robot is e-stopped
*/
bool IsEStopped() const;
static bool IsEStopped();
/**
* Check if the DS is commanding autonomous mode.
*
* @return True if the robot is being commanded to be in autonomous mode
*/
bool IsAutonomous() const;
static bool IsAutonomous();
/**
* Check if the DS is commanding autonomous mode and if it has enabled the
@@ -203,14 +189,14 @@ class DriverStation {
* @return True if the robot is being commanded to be in autonomous mode and
* enabled.
*/
bool IsAutonomousEnabled() const;
static bool IsAutonomousEnabled();
/**
* Check if the DS is commanding teleop mode.
*
* @return True if the robot is being commanded to be in teleop mode
*/
bool IsOperatorControl() const;
static bool IsOperatorControl();
/**
* Check if the DS is commanding teleop mode and if it has enabled the robot.
@@ -218,21 +204,21 @@ class DriverStation {
* @return True if the robot is being commanded to be in teleop mode and
* enabled.
*/
bool IsOperatorControlEnabled() const;
static bool IsOperatorControlEnabled();
/**
* Check if the DS is commanding test mode.
*
* @return True if the robot is being commanded to be in test mode
*/
bool IsTest() const;
static bool IsTest();
/**
* Check if the DS is attached.
*
* @return True if the DS is connected to the robot
*/
bool IsDSAttached() const;
static bool IsDSAttached();
/**
* Has a new control packet from the driver station arrived since the last
@@ -243,7 +229,7 @@ class DriverStation {
*
* @return True if the control data has been updated since the last call.
*/
bool IsNewControlData() const;
static bool IsNewControlData();
/**
* Is the driver station attached to a Field Management System?
@@ -251,21 +237,21 @@ class DriverStation {
* @return True if the robot is competing on a field being controlled by a
* Field Management System
*/
bool IsFMSAttached() const;
static bool IsFMSAttached();
/**
* Returns the game specific message provided by the FMS.
*
* @return A string containing the game specific message.
*/
std::string GetGameSpecificMessage() const;
static std::string GetGameSpecificMessage();
/**
* Returns the name of the competition event provided by the FMS.
*
* @return A string containing the event name
*/
std::string GetEventName() const;
static std::string GetEventName();
/**
* Returns the type of match being played provided by the FMS.
@@ -273,14 +259,14 @@ class DriverStation {
* @return The match type enum (kNone, kPractice, kQualification,
* kElimination)
*/
MatchType GetMatchType() const;
static MatchType GetMatchType();
/**
* Returns the match number provided by the FMS.
*
* @return The number of the match
*/
int GetMatchNumber() const;
static int GetMatchNumber();
/**
* Returns the number of times the current match has been replayed from the
@@ -288,7 +274,7 @@ class DriverStation {
*
* @return The number of replays
*/
int GetReplayNumber() const;
static int GetReplayNumber();
/**
* Return the alliance that the driver station says it is on.
@@ -297,7 +283,7 @@ class DriverStation {
*
* @return The Alliance enum (kRed, kBlue or kInvalid)
*/
Alliance GetAlliance() const;
static Alliance GetAlliance();
/**
* Return the driver station location on the field.
@@ -306,7 +292,7 @@ class DriverStation {
*
* @return The location of the driver station (1-3, 0 for invalid)
*/
int GetLocation() const;
static int GetLocation();
/**
* Wait until a new packet comes from the driver station.
@@ -319,7 +305,7 @@ class DriverStation {
* Checks if new control data has arrived since the last waitForData call
* on the current thread. If new data has not arrived, returns immediately.
*/
void WaitForData();
static void WaitForData();
/**
* Wait until a new packet comes from the driver station, or wait for a
@@ -341,7 +327,7 @@ class DriverStation {
*
* @return true if new data, otherwise false
*/
bool WaitForData(units::second_t timeout);
static bool WaitForData(units::second_t timeout);
/**
* Return the approximate match time.
@@ -358,14 +344,14 @@ class DriverStation {
*
* @return Time remaining in current match period (auto or teleop)
*/
double GetMatchTime() const;
static double GetMatchTime();
/**
* Read the battery voltage.
*
* @return The battery voltage in Volts.
*/
double GetBatteryVoltage() const;
static double GetBatteryVoltage();
/**
* Only to be used to tell the Driver Station what code you claim to be
@@ -374,7 +360,7 @@ class DriverStation {
* @param entering If true, starting disabled code; if false, leaving disabled
* code.
*/
void InDisabled(bool entering) { m_userInDisabled = entering; }
static void InDisabled(bool entering);
/**
* Only to be used to tell the Driver Station what code you claim to be
@@ -383,7 +369,7 @@ class DriverStation {
* @param entering If true, starting autonomous code; if false, leaving
* autonomous code.
*/
void InAutonomous(bool entering) { m_userInAutonomous = entering; }
static void InAutonomous(bool entering);
/**
* Only to be used to tell the Driver Station what code you claim to be
@@ -392,7 +378,7 @@ class DriverStation {
* @param entering If true, starting teleop code; if false, leaving teleop
* code.
*/
void InOperatorControl(bool entering) { m_userInTeleop = entering; }
static void InOperatorControl(bool entering);
/**
* Only to be used to tell the Driver Station what code you claim to be
@@ -400,12 +386,12 @@ class DriverStation {
*
* @param entering If true, starting test code; if false, leaving test code.
*/
void InTest(bool entering) { m_userInTest = entering; }
static void InTest(bool entering);
/**
* Forces WaitForData() to return immediately.
*/
void WakeupWaitForData();
static void WakeupWaitForData();
/**
* Allows the user to specify whether they want joystick connection warnings
@@ -414,7 +400,7 @@ class DriverStation {
*
* @param silence Whether warning messages should be silenced.
*/
void SilenceJoystickConnectionWarning(bool silence);
static void SilenceJoystickConnectionWarning(bool silence);
/**
* Returns whether joystick connection warnings are silenced. This will
@@ -422,82 +408,10 @@ class DriverStation {
*
* @return Whether joystick connection warnings are silenced.
*/
bool IsJoystickConnectionWarningSilenced() const;
protected:
/**
* Copy data from the DS task for the user.
*
* If no new data exists, it will just be returned, otherwise
* the data will be copied from the DS polling loop.
*/
void GetData();
static bool IsJoystickConnectionWarningSilenced();
private:
/**
* DriverStation constructor.
*
* This is only called once the first time GetInstance() is called
*/
DriverStation();
/**
* Reports errors related to unplugged joysticks.
*
* Throttles the errors so that they don't overwhelm the DS.
*/
void ReportJoystickUnpluggedErrorV(fmt::string_view format,
fmt::format_args args);
template <typename S, typename... Args>
inline void ReportJoystickUnpluggedError(const S& format, Args&&... args) {
ReportJoystickUnpluggedErrorV(
format, fmt::make_args_checked<Args...>(format, args...));
}
/**
* Reports errors related to unplugged joysticks.
*
* Throttles the errors so that they don't overwhelm the DS.
*/
void ReportJoystickUnpluggedWarningV(fmt::string_view format,
fmt::format_args args);
template <typename S, typename... Args>
inline void ReportJoystickUnpluggedWarning(const S& format, Args&&... args) {
ReportJoystickUnpluggedWarningV(
format, fmt::make_args_checked<Args...>(format, args...));
}
void Run();
void SendMatchData();
std::unique_ptr<MatchDataSender> m_matchDataSender;
// Joystick button rising/falling edge flags
wpi::mutex m_buttonEdgeMutex;
std::array<HAL_JoystickButtons, kJoystickPorts> m_previousButtonStates;
std::array<uint32_t, kJoystickPorts> m_joystickButtonsPressed;
std::array<uint32_t, kJoystickPorts> m_joystickButtonsReleased;
// Internal Driver Station thread
std::thread m_dsThread;
std::atomic<bool> m_isRunning{false};
mutable wpi::mutex m_waitForDataMutex;
wpi::condition_variable m_waitForDataCond;
int m_waitForDataCounter;
bool m_silenceJoystickWarning = false;
// Robot state status variables
bool m_userInDisabled = false;
bool m_userInAutonomous = false;
bool m_userInTeleop = false;
bool m_userInTest = false;
units::second_t m_nextMessageTime = 0_s;
DriverStation() = default;
};
} // namespace frc

View File

@@ -192,7 +192,6 @@ class GenericHID {
void SetRumble(RumbleType type, double value);
private:
DriverStation* m_ds;
int m_port;
int m_outputs = 0;
uint16_t m_leftRumble = 0;

View File

@@ -6,12 +6,10 @@
#include <stdint.h>
#include <memory>
#include <string>
#include <string_view>
#include <vector>
#include <networktables/NetworkTable.h>
#include <wpi/deprecated.h>
namespace frc {
@@ -36,7 +34,9 @@ class Preferences {
* Get the one and only {@link Preferences} object.
*
* @return pointer to the {@link Preferences}
* @deprecated Use the static methods
*/
WPI_DEPRECATED("Use static methods")
static Preferences* GetInstance();
/**
@@ -44,7 +44,7 @@ class Preferences {
*
* @return a vector of the keys
*/
std::vector<std::string> GetKeys();
static std::vector<std::string> GetKeys();
/**
* Returns the string at the given key. If this table does not have a value
@@ -54,8 +54,8 @@ class Preferences {
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
std::string GetString(std::string_view key,
std::string_view defaultValue = "");
static std::string GetString(std::string_view key,
std::string_view defaultValue = "");
/**
* Returns the int at the given key. If this table does not have a value for
@@ -65,7 +65,7 @@ class Preferences {
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
int GetInt(std::string_view key, int defaultValue = 0);
static int GetInt(std::string_view key, int defaultValue = 0);
/**
* Returns the double at the given key. If this table does not have a value
@@ -75,7 +75,7 @@ class Preferences {
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
double GetDouble(std::string_view key, double defaultValue = 0.0);
static double GetDouble(std::string_view key, double defaultValue = 0.0);
/**
* Returns the float at the given key. If this table does not have a value
@@ -85,7 +85,7 @@ class Preferences {
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
float GetFloat(std::string_view key, float defaultValue = 0.0);
static float GetFloat(std::string_view key, float defaultValue = 0.0);
/**
* Returns the boolean at the given key. If this table does not have a value
@@ -95,7 +95,7 @@ class Preferences {
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
bool GetBoolean(std::string_view key, bool defaultValue = false);
static bool GetBoolean(std::string_view key, bool defaultValue = false);
/**
* Returns the long (int64_t) at the given key. If this table does not have a
@@ -106,7 +106,7 @@ class Preferences {
* @param defaultValue the value to return if none exists in the table
* @return either the value in the table, or the defaultValue
*/
int64_t GetLong(std::string_view key, int64_t defaultValue = 0);
static int64_t GetLong(std::string_view key, int64_t defaultValue = 0);
/**
* Puts the given string into the preferences table.
@@ -117,7 +117,7 @@ class Preferences {
* @param key the key
* @param value the value
*/
void SetString(std::string_view key, std::string_view value);
static void SetString(std::string_view key, std::string_view value);
/**
* Puts the given string into the preferences table.
@@ -129,13 +129,13 @@ class Preferences {
* @param value the value
*/
WPI_DEPRECATED("Use SetString instead.")
void PutString(std::string_view key, std::string_view value);
static void PutString(std::string_view key, std::string_view value);
/**
* Puts the given string into the preferences table if it doesn't
* already exist.
*/
void InitString(std::string_view key, std::string_view value);
static void InitString(std::string_view key, std::string_view value);
/**
* Puts the given int into the preferences table.
@@ -145,7 +145,7 @@ class Preferences {
* @param key the key
* @param value the value
*/
void SetInt(std::string_view key, int value);
static void SetInt(std::string_view key, int value);
/**
* Puts the given int into the preferences table.
@@ -156,13 +156,13 @@ class Preferences {
* @param value the value
*/
WPI_DEPRECATED("Use SetInt instead.")
void PutInt(std::string_view key, int value);
static void PutInt(std::string_view key, int value);
/**
* Puts the given int into the preferences table if it doesn't
* already exist.
*/
void InitInt(std::string_view key, int value);
static void InitInt(std::string_view key, int value);
/**
* Puts the given double into the preferences table.
@@ -172,7 +172,7 @@ class Preferences {
* @param key the key
* @param value the value
*/
void SetDouble(std::string_view key, double value);
static void SetDouble(std::string_view key, double value);
/**
* Puts the given double into the preferences table.
@@ -183,13 +183,13 @@ class Preferences {
* @param value the value
*/
WPI_DEPRECATED("Use SetDouble instead.")
void PutDouble(std::string_view key, double value);
static void PutDouble(std::string_view key, double value);
/**
* Puts the given double into the preferences table if it doesn't
* already exist.
*/
void InitDouble(std::string_view key, double value);
static void InitDouble(std::string_view key, double value);
/**
* Puts the given float into the preferences table.
@@ -199,7 +199,7 @@ class Preferences {
* @param key the key
* @param value the value
*/
void SetFloat(std::string_view key, float value);
static void SetFloat(std::string_view key, float value);
/**
* Puts the given float into the preferences table.
@@ -210,13 +210,13 @@ class Preferences {
* @param value the value
*/
WPI_DEPRECATED("Use SetFloat instead.")
void PutFloat(std::string_view key, float value);
static void PutFloat(std::string_view key, float value);
/**
* Puts the given float into the preferences table if it doesn't
* already exist.
*/
void InitFloat(std::string_view key, float value);
static void InitFloat(std::string_view key, float value);
/**
* Puts the given boolean into the preferences table.
@@ -226,7 +226,7 @@ class Preferences {
* @param key the key
* @param value the value
*/
void SetBoolean(std::string_view key, bool value);
static void SetBoolean(std::string_view key, bool value);
/**
* Puts the given boolean into the preferences table.
@@ -237,13 +237,13 @@ class Preferences {
* @param value the value
*/
WPI_DEPRECATED("Use SetBoolean instead.")
void PutBoolean(std::string_view key, bool value);
static void PutBoolean(std::string_view key, bool value);
/**
* Puts the given boolean into the preferences table if it doesn't
* already exist.
*/
void InitBoolean(std::string_view key, bool value);
static void InitBoolean(std::string_view key, bool value);
/**
* Puts the given long (int64_t) into the preferences table.
@@ -253,7 +253,7 @@ class Preferences {
* @param key the key
* @param value the value
*/
void SetLong(std::string_view key, int64_t value);
static void SetLong(std::string_view key, int64_t value);
/**
* Puts the given long (int64_t) into the preferences table.
@@ -264,13 +264,13 @@ class Preferences {
* @param value the value
*/
WPI_DEPRECATED("Use SetLong instead.")
void PutLong(std::string_view key, int64_t value);
static void PutLong(std::string_view key, int64_t value);
/**
* Puts the given long into the preferences table if it doesn't
* already exist.
*/
void InitLong(std::string_view key, int64_t value);
static void InitLong(std::string_view key, int64_t value);
/**
* Returns whether or not there is a key with the given name.
@@ -278,29 +278,22 @@ class Preferences {
* @param key the key
* @return if there is a value at the given key
*/
bool ContainsKey(std::string_view key);
static bool ContainsKey(std::string_view key);
/**
* Remove a preference.
*
* @param key the key
*/
void Remove(std::string_view key);
static void Remove(std::string_view key);
/**
* Remove all preferences.
*/
void RemoveAll();
protected:
Preferences();
Preferences(Preferences&&) = default;
Preferences& operator=(Preferences&&) = default;
static void RemoveAll();
private:
std::shared_ptr<nt::NetworkTable> m_table;
NT_EntryListener m_listener;
Preferences() = default;
};
} // namespace frc

View File

@@ -215,15 +215,11 @@ class RobotBase {
*/
RobotBase();
virtual ~RobotBase();
virtual ~RobotBase() = default;
protected:
// m_ds isn't moved in these because DriverStation is a singleton; every
// instance of RobotBase has a reference to the same object.
RobotBase(RobotBase&&) noexcept;
RobotBase& operator=(RobotBase&&) noexcept;
DriverStation& m_ds;
RobotBase(RobotBase&&) = default;
RobotBase& operator=(RobotBase&&) = default;
static std::thread::id m_threadId;
};

View File

@@ -5,7 +5,8 @@
#pragma once
#include <functional>
#include <memory>
#include <wpi/deprecated.h>
namespace wpi {
class Sendable;
@@ -19,47 +20,58 @@ namespace frc {
*/
class LiveWindow {
public:
LiveWindow(const LiveWindow&) = delete;
LiveWindow& operator=(const LiveWindow&) = delete;
std::function<void()> enabled;
std::function<void()> disabled;
/**
* Get an instance of the LiveWindow main class.
*
* This is a singleton to guarantee that there is only a single instance
* regardless of how many times GetInstance is called.
* @deprecated Use the static methods unless guaranteeing LiveWindow is
* instantiated
*/
WPI_DEPRECATED("Use static methods")
static LiveWindow* GetInstance();
/**
* Set function to be called when LiveWindow is enabled.
*
* @param func function (or nullptr for none)
*/
static void SetEnabledCallback(std::function<void()> func);
/**
* Set function to be called when LiveWindow is disabled.
*
* @param func function (or nullptr for none)
*/
static void SetDisabledCallback(std::function<void()> func);
/**
* Enable telemetry for a single component.
*
* @param sendable component
*/
void EnableTelemetry(wpi::Sendable* component);
static void EnableTelemetry(wpi::Sendable* component);
/**
* Disable telemetry for a single component.
*
* @param sendable component
*/
void DisableTelemetry(wpi::Sendable* component);
static void DisableTelemetry(wpi::Sendable* component);
/**
* Disable ALL telemetry.
*/
void DisableAllTelemetry();
static void DisableAllTelemetry();
bool IsEnabled() const;
static bool IsEnabled();
/**
* Change the enabled status of LiveWindow.
*
* If it changes to enabled, start livewindow running otherwise stop it
*/
void SetEnabled(bool enabled);
static void SetEnabled(bool enabled);
/**
* Tell all the sensors to update (send) their values.
@@ -67,18 +79,15 @@ class LiveWindow {
* Actuators are handled through callbacks on their value changing from the
* SmartDashboard widgets.
*/
void UpdateValues();
static void UpdateValues();
private:
LiveWindow();
struct Impl;
std::unique_ptr<Impl> m_impl;
LiveWindow() = default;
/**
* Updates the entries, without using a mutex or lock.
*/
void UpdateValuesUnsafe();
static void UpdateValuesUnsafe();
};
} // namespace frc

View File

@@ -11,17 +11,18 @@
#include <networktables/NetworkTableEntry.h>
#include <networktables/NetworkTableValue.h>
#include <wpi/sendable/Sendable.h>
#include <wpi/sendable/SendableHelper.h>
#include <wpi/span.h>
#include "frc/smartdashboard/ListenerExecutor.h"
namespace wpi {
class Sendable;
} // namespace wpi
namespace frc {
class SmartDashboard : public wpi::Sendable,
public wpi::SendableHelper<SmartDashboard> {
class SmartDashboard {
public:
SmartDashboard() = delete;
static void init();
/**
@@ -433,11 +434,6 @@ class SmartDashboard : public wpi::Sendable,
* Puts all sendable data to the dashboard.
*/
static void UpdateValues();
private:
~SmartDashboard() override = default;
static detail::ListenerExecutor listenerExecutor;
};
} // namespace frc

View File

@@ -22,7 +22,7 @@ TEST_P(IsJoystickConnectedParametersTests, IsJoystickConnected) {
frc::sim::DriverStationSim::NotifyNewData();
ASSERT_EQ(std::get<3>(GetParam()),
frc::DriverStation::GetInstance().IsJoystickConnected(1));
frc::DriverStation::IsJoystickConnected(1));
}
INSTANTIATE_TEST_SUITE_P(IsConnectedTests, IsJoystickConnectedParametersTests,
@@ -43,17 +43,15 @@ TEST_P(JoystickConnectionWarningTests, JoystickConnectionWarnings) {
// Set FMS and Silence settings
frc::sim::DriverStationSim::SetFmsAttached(std::get<0>(GetParam()));
frc::sim::DriverStationSim::NotifyNewData();
frc::DriverStation::GetInstance().SilenceJoystickConnectionWarning(
std::get<1>(GetParam()));
frc::DriverStation::SilenceJoystickConnectionWarning(std::get<1>(GetParam()));
// Create joystick and attempt to retrieve button.
frc::Joystick joystick(0);
joystick.GetRawButton(1);
frc::sim::StepTiming(1_s);
EXPECT_EQ(
frc::DriverStation::GetInstance().IsJoystickConnectionWarningSilenced(),
std::get<2>(GetParam()));
EXPECT_EQ(frc::DriverStation::IsJoystickConnectionWarningSilenced(),
std::get<2>(GetParam()));
EXPECT_EQ(::testing::internal::GetCapturedStderr().substr(
0, std::get<3>(GetParam()).size()),
std::get<3>(GetParam()));

View File

@@ -8,7 +8,7 @@
#include <wpi/sendable/SendableRegistry.h>
MockActuatorSendable::MockActuatorSendable(std::string_view name) {
wpi::SendableRegistry::GetInstance().Add(this, name);
wpi::SendableRegistry::Add(this, name);
}
void MockActuatorSendable::InitSendable(wpi::SendableBuilder& builder) {

View File

@@ -19,15 +19,15 @@ class Robot : public frc::TimedRobot {
static void VisionThread() {
// Get the Axis camera from CameraServer
cs::AxisCamera camera =
frc::CameraServer::GetInstance()->AddAxisCamera("axis-camera.local");
frc::CameraServer::AddAxisCamera("axis-camera.local");
// Set the resolution
camera.SetResolution(640, 480);
// Get a CvSink. This will capture Mats from the Camera
cs::CvSink cvSink = frc::CameraServer::GetInstance()->GetVideo();
cs::CvSink cvSink = frc::CameraServer::GetVideo();
// Setup a CvSource. This will send images back to the Dashboard
cs::CvSource outputStream =
frc::CameraServer::GetInstance()->PutVideo("Rectangle", 640, 480);
frc::CameraServer::PutVideo("Rectangle", 640, 480);
// Mats are very memory expensive. Lets reuse this Mat.
cv::Mat mat;

View File

@@ -6,7 +6,6 @@
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/livewindow/LiveWindow.h>
#include <frc/motorcontrol/PWMSparkMax.h>
class Robot : public frc::TimedRobot {
@@ -50,7 +49,6 @@ class Robot : public frc::TimedRobot {
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc::Joystick m_stick{0};
frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
frc::Timer m_timer;
};

View File

@@ -23,16 +23,15 @@ class Robot : public frc::TimedRobot {
private:
static void VisionThread() {
// Get the USB camera from CameraServer
cs::UsbCamera camera =
frc::CameraServer::GetInstance()->StartAutomaticCapture();
cs::UsbCamera camera = frc::CameraServer::StartAutomaticCapture();
// Set the resolution
camera.SetResolution(640, 480);
// Get a CvSink. This will capture Mats from the Camera
cs::CvSink cvSink = frc::CameraServer::GetInstance()->GetVideo();
cs::CvSink cvSink = frc::CameraServer::GetVideo();
// Setup a CvSource. This will send images back to the Dashboard
cs::CvSource outputStream =
frc::CameraServer::GetInstance()->PutVideo("Rectangle", 640, 480);
frc::CameraServer::PutVideo("Rectangle", 640, 480);
// Mats are very memory expensive. Lets reuse this Mat.
cv::Mat mat;

View File

@@ -17,7 +17,7 @@ class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
#if defined(__linux__) || defined(_WIN32)
frc::CameraServer::GetInstance()->StartAutomaticCapture();
frc::CameraServer::StartAutomaticCapture();
#else
std::fputs("Vision only available on Linux or Windows.\n", stderr);
std::fflush(stderr);

View File

@@ -30,36 +30,36 @@ void Robot::StartCompetition() {
while (!m_exit) {
if (IsDisabled()) {
m_ds.InDisabled(true);
frc::DriverStation::InDisabled(true);
Disabled();
m_ds.InDisabled(false);
frc::DriverStation::InDisabled(false);
while (IsDisabled()) {
m_ds.WaitForData();
frc::DriverStation::WaitForData();
}
} else if (IsAutonomous()) {
m_ds.InAutonomous(true);
frc::DriverStation::InAutonomous(true);
Autonomous();
m_ds.InAutonomous(false);
frc::DriverStation::InAutonomous(false);
while (IsAutonomousEnabled()) {
m_ds.WaitForData();
frc::DriverStation::WaitForData();
}
} else if (IsTest()) {
lw.SetEnabled(true);
frc::Shuffleboard::EnableActuatorWidgets();
m_ds.InTest(true);
frc::DriverStation::InTest(true);
Test();
m_ds.InTest(false);
frc::DriverStation::InTest(false);
while (IsTest() && IsEnabled()) {
m_ds.WaitForData();
frc::DriverStation::WaitForData();
}
lw.SetEnabled(false);
frc::Shuffleboard::DisableActuatorWidgets();
} else {
m_ds.InOperatorControl(true);
frc::DriverStation::InOperatorControl(true);
Teleop();
m_ds.InOperatorControl(false);
frc::DriverStation::InOperatorControl(false);
while (IsOperatorControlEnabled()) {
m_ds.WaitForData();
frc::DriverStation::WaitForData();
}
}
}

View File

@@ -22,7 +22,7 @@ TEST(DriverStationTest, WaitForData) {
// 20ms waiting intervals * 50 = 1s
for (int i = 0; i < 50; i++) {
frc::DriverStation::GetInstance().WaitForData();
frc::DriverStation::WaitForData();
}
units::microsecond_t finalTime(frc::RobotController::GetFPGATime());

View File

@@ -40,12 +40,12 @@ class TestEnvironment : public testing::Environment {
// station returns that the robot is enabled, to ensure that tests will be
// able to run on the hardware.
HAL_ObserveUserProgramStarting();
frc::LiveWindow::GetInstance()->SetEnabled(false);
frc::LiveWindow::SetEnabled(false);
fmt::print("Started coms\n");
int enableCounter = 0;
while (!frc::DriverStation::GetInstance().IsEnabled()) {
while (!frc::DriverStation::IsEnabled()) {
if (enableCounter > 50) {
// Robot did not enable properly after 5 seconds.
// Force exit

View File

@@ -63,18 +63,14 @@ public class DriverStation {
}
private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
private double m_nextMessageTime;
private static double m_nextMessageTime;
private static class DriverStationTask implements Runnable {
private final DriverStation m_ds;
DriverStationTask(DriverStation ds) {
m_ds = ds;
}
DriverStationTask() {}
@Override
public void run() {
m_ds.run();
DriverStation.run();
}
} /* DriverStationTask */
@@ -155,7 +151,7 @@ public class DriverStation {
controlWord.forceSetDouble(0);
}
private void sendMatchData(DriverStation driverStation) {
private void sendMatchData() {
AllianceStationID allianceID = HAL.getAllianceStation();
boolean isRedAlliance = false;
int stationNumber = 1;
@@ -192,12 +188,12 @@ public class DriverStation {
int currentReplayNumber;
int currentMatchType;
int currentControlWord;
synchronized (driverStation.m_cacheDataMutex) {
currentEventName = driverStation.m_matchInfo.eventName;
currentGameSpecificMessage = driverStation.m_matchInfo.gameSpecificMessage;
currentMatchNumber = driverStation.m_matchInfo.matchNumber;
currentReplayNumber = driverStation.m_matchInfo.replayNumber;
currentMatchType = driverStation.m_matchInfo.matchType;
synchronized (DriverStation.m_cacheDataMutex) {
currentEventName = DriverStation.m_matchInfo.eventName;
currentGameSpecificMessage = DriverStation.m_matchInfo.gameSpecificMessage;
currentMatchNumber = DriverStation.m_matchInfo.matchNumber;
currentReplayNumber = DriverStation.m_matchInfo.replayNumber;
currentMatchType = DriverStation.m_matchInfo.matchType;
}
currentControlWord = HAL.nativeGetControlWord();
@@ -239,56 +235,59 @@ public class DriverStation {
private static DriverStation instance = new DriverStation();
// Joystick User Data
private HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts];
private HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts];
private HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[kJoystickPorts];
private MatchInfoData m_matchInfo = new MatchInfoData();
private static HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts];
private static HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts];
private static HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[kJoystickPorts];
private static MatchInfoData m_matchInfo = new MatchInfoData();
// Joystick Cached Data
private HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[kJoystickPorts];
private HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[kJoystickPorts];
private HALJoystickButtons[] m_joystickButtonsCache = new HALJoystickButtons[kJoystickPorts];
private MatchInfoData m_matchInfoCache = new MatchInfoData();
private static HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[kJoystickPorts];
private static HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[kJoystickPorts];
private static HALJoystickButtons[] m_joystickButtonsCache =
new HALJoystickButtons[kJoystickPorts];
private static MatchInfoData m_matchInfoCache = new MatchInfoData();
// Joystick button rising/falling edge flags
private int[] m_joystickButtonsPressed = new int[kJoystickPorts];
private int[] m_joystickButtonsReleased = new int[kJoystickPorts];
private static int[] m_joystickButtonsPressed = new int[kJoystickPorts];
private static int[] m_joystickButtonsReleased = new int[kJoystickPorts];
// preallocated byte buffer for button count
private final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1);
private static final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1);
private final MatchDataSender m_matchDataSender;
private static final MatchDataSender m_matchDataSender;
// Internal Driver Station thread
private Thread m_thread;
private static Thread m_thread;
private volatile boolean m_threadKeepAlive = true;
private static volatile boolean m_threadKeepAlive = true;
private final ReentrantLock m_cacheDataMutex = new ReentrantLock();
private static final ReentrantLock m_cacheDataMutex = new ReentrantLock();
private final Lock m_waitForDataMutex;
private final Condition m_waitForDataCond;
private int m_waitForDataCount;
private final ThreadLocal<Integer> m_lastCount = ThreadLocal.withInitial(() -> 0);
private static final Lock m_waitForDataMutex;
private static final Condition m_waitForDataCond;
private static int m_waitForDataCount;
private static final ThreadLocal<Integer> m_lastCount = ThreadLocal.withInitial(() -> 0);
private boolean m_silenceJoystickWarning;
private static boolean m_silenceJoystickWarning;
// Robot state status variables
private boolean m_userInDisabled;
private boolean m_userInAutonomous;
private boolean m_userInTeleop;
private boolean m_userInTest;
private static boolean m_userInDisabled;
private static boolean m_userInAutonomous;
private static boolean m_userInTeleop;
private static boolean m_userInTest;
// Control word variables
private final Object m_controlWordMutex;
private final ControlWord m_controlWordCache;
private long m_lastControlWordUpdate;
private static final Object m_controlWordMutex;
private static final ControlWord m_controlWordCache;
private static long m_lastControlWordUpdate;
/**
* Gets an instance of the DriverStation.
*
* @return The DriverStation.
* @deprecated Use the static methods
*/
@Deprecated
public static DriverStation getInstance() {
return DriverStation.instance;
}
@@ -299,7 +298,9 @@ public class DriverStation {
* <p>The single DriverStation instance is created statically with the instance static member
* variable.
*/
private DriverStation() {
private DriverStation() {}
static {
HAL.initialize(500, 0);
m_waitForDataCount = 0;
m_waitForDataMutex = new ReentrantLock();
@@ -321,14 +322,14 @@ public class DriverStation {
m_matchDataSender = new MatchDataSender();
m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation");
m_thread = new Thread(new DriverStationTask(), "FRCDriverStation");
m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2);
m_thread.start();
}
/** Kill the thread. */
public void release() {
public static synchronized void release() {
m_threadKeepAlive = false;
if (m_thread != null) {
try {
@@ -425,7 +426,7 @@ public class DriverStation {
* @param button The button index, beginning at 1.
* @return The state of the joystick button.
*/
public boolean getStickButton(final int stick, final int button) {
public static boolean getStickButton(final int stick, final int button) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-3");
}
@@ -459,7 +460,7 @@ public class DriverStation {
* @param button The button index, beginning at 1.
* @return Whether the joystick button was pressed since the last check.
*/
public boolean getStickButtonPressed(final int stick, final int button) {
public static boolean getStickButtonPressed(final int stick, final int button) {
if (button <= 0) {
reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
return false;
@@ -499,7 +500,7 @@ public class DriverStation {
* @param button The button index, beginning at 1.
* @return Whether the joystick button was released since the last check.
*/
public boolean getStickButtonReleased(final int stick, final int button) {
public static boolean getStickButtonReleased(final int stick, final int button) {
if (button <= 0) {
reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
return false;
@@ -540,7 +541,7 @@ public class DriverStation {
* @param axis The analog axis value to read from the joystick.
* @return The value of the axis on the joystick.
*/
public double getStickAxis(int stick, int axis) {
public static double getStickAxis(int stick, int axis) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -573,7 +574,7 @@ public class DriverStation {
* @param pov The POV to read.
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
*/
public int getStickPOV(int stick, int pov) {
public static int getStickPOV(int stick, int pov) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -605,7 +606,7 @@ public class DriverStation {
* @param stick The joystick to read.
* @return The state of the buttons on the joystick.
*/
public int getStickButtons(final int stick) {
public static int getStickButtons(final int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-3");
}
@@ -624,7 +625,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return The number of axes on the indicated joystick
*/
public int getStickAxisCount(int stick) {
public static int getStickAxisCount(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -643,7 +644,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return The number of POVs on the indicated joystick
*/
public int getStickPOVCount(int stick) {
public static int getStickPOVCount(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -662,7 +663,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return The number of buttons on the indicated joystick
*/
public int getStickButtonCount(int stick) {
public static int getStickButtonCount(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -681,7 +682,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return A boolean that returns the value of isXbox
*/
public boolean getJoystickIsXbox(int stick) {
public static boolean getJoystickIsXbox(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -695,7 +696,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return The value of type
*/
public int getJoystickType(int stick) {
public static int getJoystickType(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -709,7 +710,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return The value of name
*/
public String getJoystickName(int stick) {
public static String getJoystickName(int stick) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -724,7 +725,7 @@ public class DriverStation {
* @param axis The target axis
* @return What type of axis the axis is reporting to be
*/
public int getJoystickAxisType(int stick, int axis) {
public static int getJoystickAxisType(int stick, int axis) {
if (stick < 0 || stick >= kJoystickPorts) {
throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
}
@@ -741,7 +742,7 @@ public class DriverStation {
* @param stick The joystick port number
* @return true if a joystick is connected
*/
public boolean isJoystickConnected(int stick) {
public static boolean isJoystickConnected(int stick) {
return getStickAxisCount(stick) > 0
|| getStickButtonCount(stick) > 0
|| getStickPOVCount(stick) > 0;
@@ -752,7 +753,7 @@ public class DriverStation {
*
* @return True if the robot is enabled, false otherwise.
*/
public boolean isEnabled() {
public static boolean isEnabled() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getEnabled() && m_controlWordCache.getDSAttached();
@@ -764,7 +765,7 @@ public class DriverStation {
*
* @return True if the robot should be disabled, false otherwise.
*/
public boolean isDisabled() {
public static boolean isDisabled() {
return !isEnabled();
}
@@ -773,7 +774,7 @@ public class DriverStation {
*
* @return True if the robot is e-stopped, false otherwise.
*/
public boolean isEStopped() {
public static boolean isEStopped() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getEStop();
@@ -786,7 +787,7 @@ public class DriverStation {
*
* @return True if autonomous mode should be enabled, false otherwise.
*/
public boolean isAutonomous() {
public static boolean isAutonomous() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getAutonomous();
@@ -799,7 +800,7 @@ public class DriverStation {
*
* @return True if autonomous should be set and the robot should be enabled.
*/
public boolean isAutonomousEnabled() {
public static boolean isAutonomousEnabled() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getAutonomous() && m_controlWordCache.getEnabled();
@@ -812,7 +813,7 @@ public class DriverStation {
*
* @return True if operator-controlled mode should be enabled, false otherwise.
*/
public boolean isOperatorControl() {
public static boolean isOperatorControl() {
return !(isAutonomous() || isTest());
}
@@ -822,7 +823,7 @@ public class DriverStation {
*
* @return True if operator-controlled mode should be set and the robot should be enabled.
*/
public boolean isOperatorControlEnabled() {
public static boolean isOperatorControlEnabled() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return !m_controlWordCache.getAutonomous()
@@ -837,7 +838,7 @@ public class DriverStation {
*
* @return True if test mode should be enabled, false otherwise.
*/
public boolean isTest() {
public static boolean isTest() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getTest();
@@ -849,7 +850,7 @@ public class DriverStation {
*
* @return True if Driver Station is attached, false otherwise.
*/
public boolean isDSAttached() {
public static boolean isDSAttached() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getDSAttached();
@@ -862,7 +863,7 @@ public class DriverStation {
*
* @return True if the control data has been updated since the last call.
*/
public boolean isNewControlData() {
public static boolean isNewControlData() {
m_waitForDataMutex.lock();
try {
int currentCount = m_waitForDataCount;
@@ -881,7 +882,7 @@ public class DriverStation {
*
* @return true if the robot is competing on a field being controlled by a Field Management System
*/
public boolean isFMSAttached() {
public static boolean isFMSAttached() {
synchronized (m_controlWordMutex) {
updateControlWord(false);
return m_controlWordCache.getFMSAttached();
@@ -893,7 +894,7 @@ public class DriverStation {
*
* @return the game specific message
*/
public String getGameSpecificMessage() {
public static String getGameSpecificMessage() {
m_cacheDataMutex.lock();
try {
return m_matchInfo.gameSpecificMessage;
@@ -907,7 +908,7 @@ public class DriverStation {
*
* @return the event name
*/
public String getEventName() {
public static String getEventName() {
m_cacheDataMutex.lock();
try {
return m_matchInfo.eventName;
@@ -921,7 +922,7 @@ public class DriverStation {
*
* @return the match type
*/
public MatchType getMatchType() {
public static MatchType getMatchType() {
int matchType;
m_cacheDataMutex.lock();
try {
@@ -946,7 +947,7 @@ public class DriverStation {
*
* @return the match number
*/
public int getMatchNumber() {
public static int getMatchNumber() {
m_cacheDataMutex.lock();
try {
return m_matchInfo.matchNumber;
@@ -960,7 +961,7 @@ public class DriverStation {
*
* @return the replay number
*/
public int getReplayNumber() {
public static int getReplayNumber() {
m_cacheDataMutex.lock();
try {
return m_matchInfo.replayNumber;
@@ -974,7 +975,7 @@ public class DriverStation {
*
* @return the current alliance
*/
public Alliance getAlliance() {
public static Alliance getAlliance() {
AllianceStationID allianceStationID = HAL.getAllianceStation();
if (allianceStationID == null) {
return Alliance.Invalid;
@@ -1001,7 +1002,7 @@ public class DriverStation {
*
* @return the location of the team's driver station controls: 1, 2, or 3
*/
public int getLocation() {
public static int getLocation() {
AllianceStationID allianceStationID = HAL.getAllianceStation();
if (allianceStationID == null) {
return 0;
@@ -1030,7 +1031,7 @@ public class DriverStation {
* <p>Checks if new control data has arrived since the last waitForData call on the current
* thread. If new data has not arrived, returns immediately.
*/
public void waitForData() {
public static void waitForData() {
waitForData(0);
}
@@ -1044,7 +1045,7 @@ public class DriverStation {
* @param timeout The maximum time in seconds to wait.
* @return true if there is new data, otherwise false
*/
public boolean waitForData(double timeout) {
public static boolean waitForData(double timeout) {
long startTime = RobotController.getFPGATime();
long timeoutMicros = (long) (timeout * 1000000);
m_waitForDataMutex.lock();
@@ -1093,7 +1094,7 @@ public class DriverStation {
*
* @return Time remaining in current match period (auto or teleop) in seconds
*/
public double getMatchTime() {
public static double getMatchTime() {
return HAL.getMatchTime();
}
@@ -1104,7 +1105,7 @@ public class DriverStation {
* @param entering If true, starting disabled code; if false, leaving disabled code
*/
@SuppressWarnings("MethodName")
public void InDisabled(boolean entering) {
public static void InDisabled(boolean entering) {
m_userInDisabled = entering;
}
@@ -1115,7 +1116,7 @@ public class DriverStation {
* @param entering If true, starting autonomous code; if false, leaving autonomous code
*/
@SuppressWarnings("MethodName")
public void InAutonomous(boolean entering) {
public static void InAutonomous(boolean entering) {
m_userInAutonomous = entering;
}
@@ -1126,7 +1127,7 @@ public class DriverStation {
* @param entering If true, starting teleop code; if false, leaving teleop code
*/
@SuppressWarnings("MethodName")
public void InOperatorControl(boolean entering) {
public static void InOperatorControl(boolean entering) {
m_userInTeleop = entering;
}
@@ -1137,12 +1138,12 @@ public class DriverStation {
* @param entering If true, starting test code; if false, leaving test code
*/
@SuppressWarnings("MethodName")
public void InTest(boolean entering) {
public static void InTest(boolean entering) {
m_userInTest = entering;
}
/** Forces waitForData() to return immediately. */
public void wakeupWaitForData() {
public static void wakeupWaitForData() {
m_waitForDataMutex.lock();
m_waitForDataCount++;
m_waitForDataCond.signalAll();
@@ -1156,7 +1157,7 @@ public class DriverStation {
*
* @param silence Whether warning messages should be silenced.
*/
public void silenceJoystickConnectionWarning(boolean silence) {
public static void silenceJoystickConnectionWarning(boolean silence) {
m_silenceJoystickWarning = silence;
}
@@ -1166,7 +1167,7 @@ public class DriverStation {
*
* @return Whether joystick connection warnings are silenced.
*/
public boolean isJoystickConnectionWarningSilenced() {
public static boolean isJoystickConnectionWarningSilenced() {
return !isFMSAttached() && m_silenceJoystickWarning;
}
@@ -1174,7 +1175,7 @@ public class DriverStation {
* Copy data from the DS task for the user. If no new data exists, it will just be returned,
* otherwise the data will be copied from the DS polling loop.
*/
protected void getData() {
protected static void getData() {
// Get the status of all of the joysticks
for (byte stick = 0; stick < kJoystickPorts; stick++) {
m_joystickAxesCache[stick].m_count =
@@ -1224,14 +1225,14 @@ public class DriverStation {
}
wakeupWaitForData();
m_matchDataSender.sendMatchData(this);
m_matchDataSender.sendMatchData();
}
/**
* Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
* the DS.
*/
private void reportJoystickUnpluggedError(String message) {
private static void reportJoystickUnpluggedError(String message) {
double currentTime = Timer.getFPGATimestamp();
if (currentTime > m_nextMessageTime) {
reportError(message, false);
@@ -1243,7 +1244,7 @@ public class DriverStation {
* Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
* the DS.
*/
private void reportJoystickUnpluggedWarning(String message) {
private static void reportJoystickUnpluggedWarning(String message) {
if (isFMSAttached() || !m_silenceJoystickWarning) {
double currentTime = Timer.getFPGATimestamp();
if (currentTime > m_nextMessageTime) {
@@ -1254,7 +1255,7 @@ public class DriverStation {
}
/** Provides the service routine for the DS polling m_thread. */
private void run() {
private static void run() {
int safetyCounter = 0;
while (m_threadKeepAlive) {
HAL.waitForDSData();
@@ -1290,7 +1291,7 @@ public class DriverStation {
*
* @param force True to force an update to the cache, otherwise update if 50ms have passed.
*/
private void updateControlWord(boolean force) {
private static void updateControlWord(boolean force) {
long now = System.currentTimeMillis();
synchronized (m_controlWordMutex) {
if (now - m_lastControlWordUpdate > 50 || force) {

View File

@@ -67,14 +67,12 @@ public abstract class GenericHID {
}
}
private DriverStation m_ds;
private final int m_port;
private int m_outputs;
private short m_leftRumble;
private short m_rightRumble;
public GenericHID(int port) {
m_ds = DriverStation.getInstance();
m_port = port;
}
@@ -125,7 +123,7 @@ public abstract class GenericHID {
* @return The state of the button.
*/
public boolean getRawButton(int button) {
return m_ds.getStickButton(m_port, (byte) button);
return DriverStation.getStickButton(m_port, (byte) button);
}
/**
@@ -139,7 +137,7 @@ public abstract class GenericHID {
* @return Whether the button was pressed since the last check.
*/
public boolean getRawButtonPressed(int button) {
return m_ds.getStickButtonPressed(m_port, (byte) button);
return DriverStation.getStickButtonPressed(m_port, (byte) button);
}
/**
@@ -153,7 +151,7 @@ public abstract class GenericHID {
* @return Whether the button was released since the last check.
*/
public boolean getRawButtonReleased(int button) {
return m_ds.getStickButtonReleased(m_port, button);
return DriverStation.getStickButtonReleased(m_port, button);
}
/**
@@ -163,7 +161,7 @@ public abstract class GenericHID {
* @return The value of the axis.
*/
public double getRawAxis(int axis) {
return m_ds.getStickAxis(m_port, axis);
return DriverStation.getStickAxis(m_port, axis);
}
/**
@@ -176,7 +174,7 @@ public abstract class GenericHID {
* @return the angle of the POV in degrees, or -1 if the POV is not pressed.
*/
public int getPOV(int pov) {
return m_ds.getStickPOV(m_port, pov);
return DriverStation.getStickPOV(m_port, pov);
}
public int getPOV() {
@@ -189,7 +187,7 @@ public abstract class GenericHID {
* @return the number of axis for the current HID
*/
public int getAxisCount() {
return m_ds.getStickAxisCount(m_port);
return DriverStation.getStickAxisCount(m_port);
}
/**
@@ -198,7 +196,7 @@ public abstract class GenericHID {
* @return the number of POVs for the current HID
*/
public int getPOVCount() {
return m_ds.getStickPOVCount(m_port);
return DriverStation.getStickPOVCount(m_port);
}
/**
@@ -207,7 +205,7 @@ public abstract class GenericHID {
* @return the number of buttons for the current HID
*/
public int getButtonCount() {
return m_ds.getStickButtonCount(m_port);
return DriverStation.getStickButtonCount(m_port);
}
/**
@@ -216,7 +214,7 @@ public abstract class GenericHID {
* @return true if the HID is connected
*/
public boolean isConnected() {
return m_ds.isJoystickConnected(m_port);
return DriverStation.isJoystickConnected(m_port);
}
/**
@@ -225,7 +223,7 @@ public abstract class GenericHID {
* @return the type of the HID.
*/
public HIDType getType() {
return HIDType.of(m_ds.getJoystickType(m_port));
return HIDType.of(DriverStation.getJoystickType(m_port));
}
/**
@@ -234,7 +232,7 @@ public abstract class GenericHID {
* @return the name of the HID.
*/
public String getName() {
return m_ds.getJoystickName(m_port);
return DriverStation.getJoystickName(m_port);
}
/**
@@ -244,7 +242,7 @@ public abstract class GenericHID {
* @return the axis type of a joystick axis.
*/
public int getAxisType(int axis) {
return m_ds.getJoystickAxisType(m_port, axis);
return DriverStation.getJoystickAxisType(m_port, axis);
}
/**

View File

@@ -33,13 +33,15 @@ public final class Preferences {
/** The singleton instance. */
private static Preferences instance;
/** The network table. */
private final NetworkTable m_table;
private static final NetworkTable m_table;
/**
* Returns the preferences instance.
*
* @return the preferences instance
* @deprecated Use the static methods
*/
@Deprecated
public static synchronized Preferences getInstance() {
if (instance == null) {
instance = new Preferences();
@@ -48,7 +50,9 @@ public final class Preferences {
}
/** Creates a preference class. */
private Preferences() {
private Preferences() {}
static {
m_table = NetworkTableInstance.getDefault().getTable(TABLE_NAME);
m_table.getEntry(".type").setString("RobotPreferences");
// Listener to set all Preferences values to persistent
@@ -64,7 +68,7 @@ public final class Preferences {
*
* @return a collection of the keys
*/
public Collection<String> getKeys() {
public static Collection<String> getKeys() {
return m_table.getKeys();
}
@@ -75,7 +79,7 @@ public final class Preferences {
* @param value the value
* @throws NullPointerException if value is null
*/
public void setString(String key, String value) {
public static void setString(String key, String value) {
requireNonNullParam(value, "value", "setString");
NetworkTableEntry entry = m_table.getEntry(key);
@@ -92,7 +96,7 @@ public final class Preferences {
* @deprecated Use {@link #setString(String, String)}
*/
@Deprecated
public void putString(String key, String value) {
public static void putString(String key, String value) {
setString(key, value);
}
@@ -102,7 +106,7 @@ public final class Preferences {
* @param key The key
* @param value The value
*/
public void initString(String key, String value) {
public static void initString(String key, String value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDefaultString(value);
}
@@ -113,7 +117,7 @@ public final class Preferences {
* @param key the key
* @param value the value
*/
public void setInt(String key, int value) {
public static void setInt(String key, int value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDouble(value);
entry.setPersistent();
@@ -127,7 +131,7 @@ public final class Preferences {
* @deprecated Use {@link #setInt(String, int)}
*/
@Deprecated
public void putInt(String key, int value) {
public static void putInt(String key, int value) {
setInt(key, value);
}
@@ -137,7 +141,7 @@ public final class Preferences {
* @param key The key
* @param value The value
*/
public void initInt(String key, int value) {
public static void initInt(String key, int value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDefaultDouble(value);
}
@@ -148,7 +152,7 @@ public final class Preferences {
* @param key the key
* @param value the value
*/
public void setDouble(String key, double value) {
public static void setDouble(String key, double value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDouble(value);
entry.setPersistent();
@@ -162,7 +166,7 @@ public final class Preferences {
* @deprecated Use {@link #setDouble(String, double)}
*/
@Deprecated
public void putDouble(String key, double value) {
public static void putDouble(String key, double value) {
setDouble(key, value);
}
@@ -172,7 +176,7 @@ public final class Preferences {
* @param key The key
* @param value The value
*/
public void initDouble(String key, double value) {
public static void initDouble(String key, double value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDefaultDouble(value);
}
@@ -183,7 +187,7 @@ public final class Preferences {
* @param key the key
* @param value the value
*/
public void setFloat(String key, float value) {
public static void setFloat(String key, float value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDouble(value);
entry.setPersistent();
@@ -197,7 +201,7 @@ public final class Preferences {
* @deprecated Use {@link #setFloat(String, float)}
*/
@Deprecated
public void putFloat(String key, float value) {
public static void putFloat(String key, float value) {
setFloat(key, value);
}
@@ -207,7 +211,7 @@ public final class Preferences {
* @param key The key
* @param value The value
*/
public void initFloat(String key, float value) {
public static void initFloat(String key, float value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDefaultDouble(value);
}
@@ -218,7 +222,7 @@ public final class Preferences {
* @param key the key
* @param value the value
*/
public void setBoolean(String key, boolean value) {
public static void setBoolean(String key, boolean value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setBoolean(value);
entry.setPersistent();
@@ -232,7 +236,7 @@ public final class Preferences {
* @deprecated Use {@link #setBoolean(String, boolean)}
*/
@Deprecated
public void putBoolean(String key, boolean value) {
public static void putBoolean(String key, boolean value) {
setBoolean(key, value);
}
@@ -242,7 +246,7 @@ public final class Preferences {
* @param key The key
* @param value The value
*/
public void initBoolean(String key, boolean value) {
public static void initBoolean(String key, boolean value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDefaultBoolean(value);
}
@@ -253,7 +257,7 @@ public final class Preferences {
* @param key the key
* @param value the value
*/
public void setLong(String key, long value) {
public static void setLong(String key, long value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDouble(value);
entry.setPersistent();
@@ -267,7 +271,7 @@ public final class Preferences {
* @deprecated Use {@link #setLong(String, long)}
*/
@Deprecated
public void putLong(String key, long value) {
public static void putLong(String key, long value) {
setLong(key, value);
}
@@ -277,7 +281,7 @@ public final class Preferences {
* @param key The key
* @param value The value
*/
public void initLong(String key, long value) {
public static void initLong(String key, long value) {
NetworkTableEntry entry = m_table.getEntry(key);
entry.setDefaultDouble(value);
}
@@ -288,7 +292,7 @@ public final class Preferences {
* @param key the key
* @return if there is a value at the given key
*/
public boolean containsKey(String key) {
public static boolean containsKey(String key) {
return m_table.containsKey(key);
}
@@ -297,12 +301,12 @@ public final class Preferences {
*
* @param key the key
*/
public void remove(String key) {
public static void remove(String key) {
m_table.delete(key);
}
/** Remove all preferences. */
public void removeAll() {
public static void removeAll() {
for (String key : m_table.getKeys()) {
if (!".type".equals(key)) {
remove(key);
@@ -318,7 +322,7 @@ public final class Preferences {
* @param backup the value to return if none exists in the table
* @return either the value in the table, or the backup
*/
public String getString(String key, String backup) {
public static String getString(String key, String backup) {
return m_table.getEntry(key).getString(backup);
}
@@ -330,7 +334,7 @@ public final class Preferences {
* @param backup the value to return if none exists in the table
* @return either the value in the table, or the backup
*/
public int getInt(String key, int backup) {
public static int getInt(String key, int backup) {
return (int) m_table.getEntry(key).getDouble(backup);
}
@@ -342,7 +346,7 @@ public final class Preferences {
* @param backup the value to return if none exists in the table
* @return either the value in the table, or the backup
*/
public double getDouble(String key, double backup) {
public static double getDouble(String key, double backup) {
return m_table.getEntry(key).getDouble(backup);
}
@@ -354,7 +358,7 @@ public final class Preferences {
* @param backup the value to return if none exists in the table
* @return either the value in the table, or the backup
*/
public boolean getBoolean(String key, boolean backup) {
public static boolean getBoolean(String key, boolean backup) {
return m_table.getEntry(key).getBoolean(backup);
}
@@ -366,7 +370,7 @@ public final class Preferences {
* @param backup the value to return if none exists in the table
* @return either the value in the table, or the backup
*/
public float getFloat(String key, float backup) {
public static float getFloat(String key, float backup) {
return (float) m_table.getEntry(key).getDouble(backup);
}
@@ -378,7 +382,7 @@ public final class Preferences {
* @param backup the value to return if none exists in the table
* @return either the value in the table, or the backup
*/
public long getLong(String key, long backup) {
public static long getLong(String key, long backup) {
return (long) m_table.getEntry(key).getDouble(backup);
}
}

View File

@@ -123,8 +123,6 @@ public abstract class RobotBase implements AutoCloseable {
});
}
protected final DriverStation m_ds;
/**
* Constructor for a generic robot program. User code should be placed in the constructor that
* runs before the Autonomous or Operator Control period starts. The constructor will run to
@@ -144,7 +142,6 @@ public abstract class RobotBase implements AutoCloseable {
} else {
inst.startServer();
}
m_ds = DriverStation.getInstance();
inst.getTable("LiveWindow").getSubTable(".status").getEntry("LW Enabled").setBoolean(false);
LiveWindow.setEnabled(false);
@@ -182,7 +179,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the Robot is currently disabled by the field controls.
*/
public boolean isDisabled() {
return m_ds.isDisabled();
return DriverStation.isDisabled();
}
/**
@@ -191,7 +188,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the Robot is currently enabled by the field controls.
*/
public boolean isEnabled() {
return m_ds.isEnabled();
return DriverStation.isEnabled();
}
/**
@@ -200,7 +197,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating Autonomously.
*/
public boolean isAutonomous() {
return m_ds.isAutonomous();
return DriverStation.isAutonomous();
}
/**
@@ -210,7 +207,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating autonomously while enabled.
*/
public boolean isAutonomousEnabled() {
return m_ds.isAutonomousEnabled();
return DriverStation.isAutonomousEnabled();
}
/**
@@ -219,7 +216,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Test mode.
*/
public boolean isTest() {
return m_ds.isTest();
return DriverStation.isTest();
}
/**
@@ -229,7 +226,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Tele-Op mode.
*/
public boolean isOperatorControl() {
return m_ds.isOperatorControl();
return DriverStation.isOperatorControl();
}
/**
@@ -239,7 +236,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return True if the robot is currently operating in Tele-Op mode while enabled.
*/
public boolean isOperatorControlEnabled() {
return m_ds.isOperatorControlEnabled();
return DriverStation.isOperatorControlEnabled();
}
/**
@@ -248,7 +245,7 @@ public abstract class RobotBase implements AutoCloseable {
* @return Has new data arrived over the network since the last time this function was called?
*/
public boolean isNewDataAvailable() {
return m_ds.isNewControlData();
return DriverStation.isNewControlData();
}
/** Provide an alternate "main loop" via startCompetition(). */

View File

@@ -7,27 +7,27 @@ package edu.wpi.first.wpilibj;
@SuppressWarnings("MissingJavadocMethod")
public final class RobotState {
public static boolean isDisabled() {
return DriverStation.getInstance().isDisabled();
return DriverStation.isDisabled();
}
public static boolean isEnabled() {
return DriverStation.getInstance().isEnabled();
return DriverStation.isEnabled();
}
public static boolean isEStopped() {
return DriverStation.getInstance().isEStopped();
return DriverStation.isEStopped();
}
public static boolean isOperatorControl() {
return DriverStation.getInstance().isOperatorControl();
return DriverStation.isOperatorControl();
}
public static boolean isAutonomous() {
return DriverStation.getInstance().isAutonomous();
return DriverStation.isAutonomous();
}
public static boolean isTest() {
return DriverStation.getInstance().isTest();
return DriverStation.isTest();
}
private RobotState() {}

View File

@@ -26,7 +26,7 @@ public class Timer {
* @return Time remaining in current match period (auto or teleop) in seconds
*/
public static double getMatchTime() {
return DriverStation.getInstance().getMatchTime();
return DriverStation.getMatchTime();
}
/**

View File

@@ -312,7 +312,7 @@ public final class DriverStationSim {
/** Updates DriverStation data so that new values are visible to the user program. */
public static void notifyNewData() {
DriverStationDataJNI.notifyNewData();
DriverStation.getInstance().waitForData();
DriverStation.waitForData();
}
/**

View File

@@ -44,7 +44,7 @@
*
* {@literal @}Override
* public void robotInit() {
* usbCamera = CameraServer.getInstance().startAutomaticCapture(0);
* usbCamera = CameraServer.startAutomaticCapture(0);
* findTotePipeline = new MyFindTotePipeline();
* findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
* }

View File

@@ -23,7 +23,7 @@ class DriverStationTest {
DriverStationSim.notifyNewData();
assertEquals(expected, DriverStation.getInstance().isJoystickConnected(1));
assertEquals(expected, DriverStation.isJoystickConnected(1));
}
static Stream<Arguments> isConnectedProvider() {
@@ -41,8 +41,8 @@ class DriverStationTest {
DriverStationSim.setFmsAttached(fms);
DriverStationSim.notifyNewData();
DriverStation.getInstance().silenceJoystickConnectionWarning(silence);
assertEquals(expected, DriverStation.getInstance().isJoystickConnectionWarningSilenced());
DriverStation.silenceJoystickConnectionWarning(silence);
assertEquals(expected, DriverStation.isJoystickConnectionWarningSilenced());
}
static Stream<Arguments> connectionWarningProvider() {

View File

@@ -28,14 +28,14 @@ public class Robot extends TimedRobot {
new Thread(
() -> {
// Get the Axis camera from CameraServer
AxisCamera camera = CameraServer.getInstance().addAxisCamera("axis-camera.local");
AxisCamera camera = CameraServer.addAxisCamera("axis-camera.local");
// Set the resolution
camera.setResolution(640, 480);
// Get a CvSink. This will capture Mats from the camera
CvSink cvSink = CameraServer.getInstance().getVideo();
CvSink cvSink = CameraServer.getVideo();
// Setup a CvSource. This will send images back to the Dashboard
CvSource outputStream = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
CvSource outputStream = CameraServer.putVideo("Rectangle", 640, 480);
// Mats are very memory expensive. Lets reuse this Mat.
Mat mat = new Mat();

View File

@@ -28,14 +28,14 @@ public class Robot extends TimedRobot {
new Thread(
() -> {
// Get the UsbCamera from CameraServer
UsbCamera camera = CameraServer.getInstance().startAutomaticCapture();
UsbCamera camera = CameraServer.startAutomaticCapture();
// Set the resolution
camera.setResolution(640, 480);
// Get a CvSink. This will capture Mats from the camera
CvSink cvSink = CameraServer.getInstance().getVideo();
CvSink cvSink = CameraServer.getVideo();
// Setup a CvSource. This will send images back to the Dashboard
CvSource outputStream = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
CvSource outputStream = CameraServer.putVideo("Rectangle", 640, 480);
// Mats are very memory expensive. Lets reuse this Mat.
Mat mat = new Mat();

View File

@@ -15,6 +15,6 @@ import edu.wpi.first.wpilibj.TimedRobot;
public class Robot extends TimedRobot {
@Override
public void robotInit() {
CameraServer.getInstance().startAutomaticCapture();
CameraServer.startAutomaticCapture();
}
}

View File

@@ -5,6 +5,7 @@
package edu.wpi.first.wpilibj.templates.educational;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
/** Educational robot base class. */
@@ -38,32 +39,32 @@ public class EducationalRobot extends RobotBase {
while (!Thread.currentThread().isInterrupted() && !m_exit) {
if (isDisabled()) {
m_ds.InDisabled(true);
DriverStation.InDisabled(true);
disabled();
m_ds.InDisabled(false);
DriverStation.InDisabled(false);
while (isDisabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
} else if (isAutonomous()) {
m_ds.InAutonomous(true);
DriverStation.InAutonomous(true);
autonomous();
m_ds.InAutonomous(false);
DriverStation.InAutonomous(false);
while (isAutonomousEnabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
} else if (isTest()) {
m_ds.InTest(true);
DriverStation.InTest(true);
test();
m_ds.InTest(false);
DriverStation.InTest(false);
while (isTest() && isEnabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
} else {
m_ds.InOperatorControl(true);
DriverStation.InOperatorControl(true);
teleop();
m_ds.InOperatorControl(false);
DriverStation.InOperatorControl(false);
while (isOperatorControlEnabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
}
}

View File

@@ -5,6 +5,7 @@
package edu.wpi.first.wpilibj.templates.robotbaseskeleton;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
@@ -35,36 +36,36 @@ public class Robot extends RobotBase {
while (!Thread.currentThread().isInterrupted() && !m_exit) {
if (isDisabled()) {
m_ds.InDisabled(true);
DriverStation.InDisabled(true);
disabled();
m_ds.InDisabled(false);
DriverStation.InDisabled(false);
while (isDisabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
} else if (isAutonomous()) {
m_ds.InAutonomous(true);
DriverStation.InAutonomous(true);
autonomous();
m_ds.InAutonomous(false);
DriverStation.InAutonomous(false);
while (isAutonomousEnabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
} else if (isTest()) {
LiveWindow.setEnabled(true);
Shuffleboard.enableActuatorWidgets();
m_ds.InTest(true);
DriverStation.InTest(true);
test();
m_ds.InTest(false);
DriverStation.InTest(false);
while (isTest() && isEnabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
LiveWindow.setEnabled(false);
Shuffleboard.disableActuatorWidgets();
} else {
m_ds.InOperatorControl(true);
DriverStation.InOperatorControl(true);
teleop();
m_ds.InOperatorControl(false);
DriverStation.InOperatorControl(false);
while (isOperatorControlEnabled()) {
m_ds.waitForData();
DriverStation.waitForData();
}
}
}

View File

@@ -66,7 +66,7 @@ public class CounterTest extends AbstractComsSetup {
// port}.
// These data are hard-coded into the class, but they could be
// generated or loaded in any way you like.
return TestBench.getInstance().getDIOCrossConnectCollection();
return TestBench.getDIOCrossConnectCollection();
}
@BeforeClass

View File

@@ -58,7 +58,7 @@ public class DIOCrossConnectTest extends AbstractInterruptTest {
// port}.
// These data are hard-coded into the class, but they could be
// generated or loaded in any way you like.
return TestBench.getInstance().getDIOCrossConnectCollection();
return TestBench.getDIOCrossConnectCollection();
}
@AfterClass

View File

@@ -26,7 +26,7 @@ public class DriverStationTest extends AbstractComsSetup {
// Wait for data 50 times
for (int i = 0; i < 50; i++) {
DriverStation.getInstance().waitForData();
DriverStation.waitForData();
}
long endTime = RobotController.getFPGATime();
long difference = endTime - startTime;

View File

@@ -43,7 +43,7 @@ public class EncoderTest extends AbstractComsSetup {
*/
@Parameters
public static Collection<Integer[]> generateData() {
return TestBench.getInstance().getEncoderDIOCrossConnectCollection();
return TestBench.getEncoderDIOCrossConnectCollection();
}
/**

View File

@@ -30,7 +30,7 @@ public class GyroTest extends AbstractComsSetup {
@Before
public void setUp() {
logger.fine("Setup: TiltPan camera");
m_tpcam = TestBench.getInstance().getTiltPanCam();
m_tpcam = TestBench.getTiltPanCam();
m_tpcam.setup();
}

View File

@@ -58,9 +58,7 @@ public class MotorEncoderTest extends AbstractComsSetup {
// logger.fine("Loading the MotorList");
return Arrays.asList(
new MotorEncoderFixture<?>[][] {
{TestBench.getInstance().getTalonPair()},
{TestBench.getInstance().getVictorPair()},
{TestBench.getInstance().getJaguarPair()}
{TestBench.getTalonPair()}, {TestBench.getVictorPair()}, {TestBench.getJaguarPair()}
});
}

View File

@@ -46,9 +46,7 @@ public class MotorInvertingTest extends AbstractComsSetup {
// logger.fine("Loading the MotorList");
return Arrays.asList(
new MotorEncoderFixture<?>[][] {
{TestBench.getInstance().getTalonPair()},
{TestBench.getInstance().getVictorPair()},
{TestBench.getInstance().getJaguarPair()}
{TestBench.getTalonPair()}, {TestBench.getVictorPair()}, {TestBench.getJaguarPair()}
});
}

View File

@@ -60,7 +60,7 @@ public class PDPTest extends AbstractComsSetup {
@Parameters(name = "{index}: {0}, Expected Stopped Current Draw: {1}")
public static Collection<Object[]> generateData() {
// logger.fine("Loading the MotorList");
return Arrays.asList(new Object[][] {{TestBench.getInstance().getTalonPair(), 0.0}});
return Arrays.asList(new Object[][] {{TestBench.getTalonPair(), 0.0}});
}
@After

View File

@@ -72,9 +72,9 @@ public class PIDTest extends AbstractComsSetup {
data.addAll(
Arrays.asList(
new Object[][] {
{kp, ki, kd, TestBench.getInstance().getTalonPair()},
{kp, ki, kd, TestBench.getInstance().getVictorPair()},
{kp, ki, kd, TestBench.getInstance().getJaguarPair()}
{kp, ki, kd, TestBench.getTalonPair()},
{kp, ki, kd, TestBench.getVictorPair()},
{kp, ki, kd, TestBench.getJaguarPair()}
}));
}
return data;

Some files were not shown because too many files have changed in this diff Show More