Update allwpilib and associated libraries
There's a new required version with critical updates.
Change-Id: I4c4d39fe81378928fcd21ce8ee1c84654cbe763c
diff --git a/WORKSPACE b/WORKSPACE
index 1f9b144..b1199c7 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -323,7 +323,7 @@
path = "third_party/ceres",
)
-# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/api-cpp/5.12.1/.
+# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/api-cpp/5.14.1/.
new_http_archive(
name = "ctre_phoenix_api_cpp_headers_2019",
build_file_content = """
@@ -333,13 +333,13 @@
hdrs = glob(['ctre/phoenix/**/*.h']),
)
""",
- sha256 = "eb625897a16f1894a4854dd60f68f495875f9b0baed826ea1a38f0afdb14712d",
+ sha256 = "f11f83ea6854229a1c4381d5e6a3917be6a062eb266ad14e4c4c9067ec3cd446",
urls = [
- "http://www.frc971.org/Build-Dependencies/api-cpp-5.12.1-headers.zip",
+ "http://www.frc971.org/Build-Dependencies/api-cpp-5.14.1-headers.zip",
],
)
-# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/api-cpp/5.12.1/.
+# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/api-cpp/5.14.1/.
new_http_archive(
name = "ctre_phoenix_api_cpp_athena_2019",
build_file_content = """
@@ -353,13 +353,13 @@
],
)
""",
- sha256 = "f6afe6d35b8abcef16b09b2e65c59049091c88a0eb471bf65e77bc510de3f571",
+ sha256 = "0a976b86e887a75f0565fd7069db25e06ff0b76d2eebc294f23d81636b165381",
urls = [
- "http://www.frc971.org/Build-Dependencies/api-cpp-5.12.1-linuxathenastatic.zip",
+ "http://www.frc971.org/Build-Dependencies/api-cpp-5.14.1-linuxathenastatic.zip",
],
)
-# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/cci/5.12.1/.
+# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/cci/5.14.1/.
new_http_archive(
name = "ctre_phoenix_cci_headers_2019",
build_file_content = """
@@ -369,13 +369,13 @@
hdrs = glob(['ctre/phoenix/**/*.h']),
)
""",
- sha256 = "98f30180fc2cdd8119482364b7d47d38ee02b7746aeecd4cf1d2c25cbde7837b",
+ sha256 = "0ce3d1cc916d9ebfcd19a5622736193cbac4f799205df155480943895ac78e45",
urls = [
- "http://www.frc971.org/Build-Dependencies/cci-5.12.1-headers.zip",
+ "http://www.frc971.org/Build-Dependencies/cci-5.14.1-headers.zip",
],
)
-# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/cci/5.12.1/.
+# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/cci/5.14.1/.
new_http_archive(
name = "ctre_phoenix_cci_athena_2019",
build_file_content = """
@@ -386,13 +386,13 @@
restricted_to = ['@//tools:roborio'],
)
""",
- sha256 = "2fdc8dd0c2bcb463cd7a5082f2a378554497861508b4257b0cc4bab6a4a8316f",
+ sha256 = "00b7e4abb1190924e9b31761951494264beebf4eefb64901000034dafaf2e8bc",
urls = [
- "http://www.frc971.org/Build-Dependencies/cci-5.12.1-linuxathenastatic.zip",
+ "http://www.frc971.org/Build-Dependencies/cci-5.14.1-linuxathenastatic.zip",
],
)
-# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/core/5.12.1/.
+# Downloaded from http://devsite.ctr-electronics.com/maven/release/com/ctre/phoenix/core/5.14.1/.
new_http_archive(
name = "ctre_phoenix_core_headers_2019",
build_file_content = """
@@ -402,8 +402,8 @@
hdrs = glob(['ctre/phoenix/**/*.h']),
)
""",
- sha256 = "ddd7d740787279359d9773a4096696770411aec22e092c20749a4f5388779edf",
+ sha256 = "b74bf1bd5428cd6d7f7c3cf293b5bf8c009126eb2271d68ed070756427de5f7a",
urls = [
- "http://www.frc971.org/Build-Dependencies/core-5.12.1-headers.zip",
+ "http://www.frc971.org/Build-Dependencies/core-5.14.1-headers.zip",
],
)
diff --git a/third_party/allwpilib_2019/.wpilib/wpilib_preferences.json b/third_party/allwpilib_2019/.wpilib/wpilib_preferences.json
new file mode 100644
index 0000000..0c8975e
--- /dev/null
+++ b/third_party/allwpilib_2019/.wpilib/wpilib_preferences.json
@@ -0,0 +1,6 @@
+{
+ "enableCppIntellisense": true,
+ "currentLanguage": "cpp",
+ "projectYear": "2019",
+ "teamNumber": 0
+}
diff --git a/third_party/allwpilib_2019/README.md b/third_party/allwpilib_2019/README.md
index 8bb93b3..c3fdeb4 100644
--- a/third_party/allwpilib_2019/README.md
+++ b/third_party/allwpilib_2019/README.md
@@ -25,10 +25,10 @@
- A C++ compiler
- On Linux, GCC works fine
- - On Windows, you need Visual Studio 2015 (the free community edition works fine).
+ - On Windows, you need Visual Studio 2017 (the free community edition works fine).
Make sure to select the C++ Programming Language for installation
-- [ARM Compiler Toolchain](http://first.wpi.edu/FRC/roborio/toolchains/)
- * Note that for 2017-2018 and beyond, you will need version 5 or greater of GCC
+- [ARM Compiler Toolchain](https://github.com/wpilibsuite/toolchain-builder/releases)
+ * Note that for 2019 and beyond, you should use version 6 or greater of GCC
- Doxygen (Only required if you want to build the C++ documentation)
## Setup
@@ -79,23 +79,18 @@
wpiformat can be executed anywhere in the repository via `py -3 -m wpiformat` on Windows or `python3 -m wpiformat` on other platforms.
+CMake is also supported for building. See [README-CMAKE.md](README-CMAKE.md).
+
## Publishing
-If you are building to test with the Eclipse plugins or just want to export the build as a Maven-style dependency, simply run the `publish` task. This task will publish all available packages to ~/releases/maven/development. If you need to publish the project to a different repo, you can specify it with `-Prepo=repo_name`. Valid options are:
+If you are building to test with other dependencies or just want to export the build as a Maven-style dependency, simply run the `publish` task. This task will publish all available packages to ~/releases/maven/development. If you need to publish the project to a different repo, you can specify it with `-Prepo=repo_name`. Valid options are:
- development - The default repo.
- beta - Publishes to ~/releases/maven/beta.
- stable - Publishes to ~/releases/maven/stable.
- release - Publishes to ~/releases/maven/release.
-The following maven targets a published by this task:
-
-- edu.wpi.first.wpilib.cmake:cpp-root:1.0.0 - roboRIO C++
-- edu.wpi.first.wpilibc.simulation:WPILibCSim:0.1.0 - Simulation C++
-- edu.wpi.first.wpilibj:wpilibJavaFinal:0.1.0-SNAPSHOT - roboRIO Java
-- edu.wpi.first.wpilibj:wpilibJavaSim:0.1.0-SNAPSHOT - Simulation Java
-- edu.wpi.first.wpilibj.simulation:SimDS:0.1.0-SNAPSHOT - The driverstation for controlling simulation.
-- org.gazebosim:JavaGazebo:0.1.0-SNAPSHOT - Gazebo protocol for Java.
+The maven artifacts are described in [MavenArtifacts.md](MavenArtifacts.md)
## Structure and Organization
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
index 58da593..fe54225 100644
--- a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
@@ -65,6 +65,8 @@
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
+ // 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
@@ -157,14 +159,20 @@
return values;
}
- @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+ @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP", "PMD.CyclomaticComplexity"})
private synchronized void updateStreamValues() {
// Over all the sinks...
for (VideoSink i : m_sinks.values()) {
int sink = i.getHandle();
// Get the source's subtable (if none exists, we're done)
- int source = CameraServerJNI.getSinkSource(sink);
+ int source;
+ Integer fixedSource = m_fixedSources.get(sink);
+ if (fixedSource != null) {
+ source = fixedSource;
+ } else {
+ source = CameraServerJNI.getSinkSource(sink);
+ }
if (source == 0) {
continue;
}
@@ -295,6 +303,7 @@
m_defaultUsbDevice = new AtomicInteger();
m_sources = new Hashtable<>();
m_sinks = new Hashtable<>();
+ m_fixedSources = new Hashtable<>();
m_tables = new Hashtable<>();
m_publishTable = NetworkTableInstance.getDefault().getTable(kPublishName);
m_nextPort = kBasePort;
@@ -597,6 +606,21 @@
}
/**
+ * Adds a virtual camera for switching between two streams. Unlike the
+ * other addCamera methods, this returns a VideoSink rather than a
+ * VideoSource. Calling setSource() on the returned object can be used
+ * to switch the actual source of the stream.
+ */
+ public MjpegServer addSwitchedCamera(String name) {
+ // create a dummy CvSource
+ CvSource source = new CvSource(name, VideoMode.PixelFormat.kMJPEG, 160, 120, 30);
+ MjpegServer server = startAutomaticCapture(source);
+ m_fixedSources.put(server.getHandle(), source.getHandle());
+
+ return server;
+ }
+
+ /**
* Get OpenCV access to the primary camera feed. This allows you to
* get images from the camera for image processing on the roboRIO.
*
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
index 3069d22..a3caf5c 100644
--- a/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
@@ -33,10 +33,11 @@
void UpdateStreamValues();
wpi::mutex m_mutex;
- std::atomic<int> m_defaultUsbDevice;
+ std::atomic<int> m_defaultUsbDevice{0};
std::string m_primarySourceName;
wpi::StringMap<cs::VideoSource> m_sources;
wpi::StringMap<cs::VideoSink> m_sinks;
+ wpi::DenseMap<CS_Sink, CS_Source> m_fixedSources;
wpi::DenseMap<CS_Source, std::shared_ptr<nt::NetworkTable>> m_tables;
std::shared_ptr<nt::NetworkTable> m_publishTable;
cs::VideoListener m_videoListener;
@@ -156,7 +157,8 @@
CS_Sink sink = i.second.GetHandle();
// Get the source's subtable (if none exists, we're done)
- CS_Source source = cs::GetSinkSource(sink, &status);
+ CS_Source source = m_fixedSources.lookup(sink);
+ if (source == 0) source = cs::GetSinkSource(sink, &status);
if (source == 0) continue;
auto table = m_tables.lookup(source);
if (table) {
@@ -538,6 +540,15 @@
return camera;
}
+cs::MjpegServer CameraServer::AddSwitchedCamera(const wpi::Twine& 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();
+
+ return server;
+}
+
cs::MjpegServer CameraServer::StartAutomaticCapture(
const cs::VideoSource& camera) {
AddCamera(camera);
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.h b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.h
index 42a9f0c..46c2448 100644
--- a/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.h
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.h
@@ -174,6 +174,14 @@
std::initializer_list<T> hosts);
/**
+ * Adds a virtual camera for switching between two streams. Unlike the
+ * other addCamera methods, this returns a VideoSink rather than a
+ * VideoSource. Calling SetSource() on the returned object can be used
+ * to switch the actual source of the stream.
+ */
+ cs::MjpegServer AddSwitchedCamera(const wpi::Twine& name);
+
+ /**
* Get OpenCV access to the primary camera feed. This allows you to
* get images from the camera for image processing on the roboRIO.
*
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.cpp
index 9dd6f33..f548f9c 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.cpp
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.cpp
@@ -111,13 +111,13 @@
void StartStream() {
std::lock_guard<wpi::mutex> lock(m_mutex);
- m_source->EnableSink();
+ if (m_source) m_source->EnableSink();
m_streaming = true;
}
void StopStream() {
std::lock_guard<wpi::mutex> lock(m_mutex);
- m_source->DisableSink();
+ if (m_source) m_source->DisableSink();
m_streaming = false;
}
};
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.cpp b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.cpp
index 6976095..4f51976 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.cpp
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.cpp
@@ -9,6 +9,7 @@
#include <wpi/STLExtras.h>
#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
#include "UsbUtil.h"
@@ -151,6 +152,9 @@
propKind = CS_PROP_BOOLEAN;
break;
case V4L2_CTRL_TYPE_INTEGER_MENU:
+ propKind = CS_PROP_ENUM;
+ intMenu = true;
+ break;
case V4L2_CTRL_TYPE_MENU:
propKind = CS_PROP_ENUM;
break;
@@ -243,7 +247,12 @@
for (int i = prop->minimum; i <= prop->maximum; ++i) {
qmenu.index = static_cast<__u32>(i);
if (TryIoctl(fd, VIDIOC_QUERYMENU, &qmenu) != 0) continue;
- prop->enumChoices[i] = reinterpret_cast<const char*>(qmenu.name);
+ if (prop->intMenu) {
+ wpi::raw_string_ostream os(prop->enumChoices[i]);
+ os << qmenu.value;
+ } else {
+ prop->enumChoices[i] = reinterpret_cast<const char*>(qmenu.name);
+ }
}
}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.h b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.h
index 446deab..d3569cc 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.h
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.h
@@ -71,6 +71,9 @@
unsigned id{0}; // implementation-level id
int type{0}; // implementation type, not CS_PropertyKind!
+
+ // If the enum property is integer rather than string
+ bool intMenu{false};
};
} // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkUtil.cpp b/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkUtil.cpp
index 99e734a..e994eb8 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkUtil.cpp
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkUtil.cpp
@@ -5,27 +5,12 @@
/* the project. */
/*----------------------------------------------------------------------------*/
-#include <winsock2.h> // NOLINT(build/include_order)
-
-#include <iphlpapi.h> // NOLINT(build/include_order)
-
-#include <ws2tcpip.h> // NOLINT(build/include_order)
-
#include <uv.h>
-#include <iostream>
-
#include "cscore_cpp.h"
-#pragma comment(lib, "IPHLPAPI.lib")
#pragma comment(lib, "Ws2_32.lib")
-#define WORKING_BUFFER_SIZE 15000
-#define MAX_TRIES 3
-
-#define MALLOC(x) HeapAlloc(GetProcessHeap(), 0, (x))
-#define FREE(x) HeapFree(GetProcessHeap(), 0, (x))
-
namespace cs {
std::vector<std::string> GetNetworkInterfaces() {
@@ -40,80 +25,18 @@
for (int i = 0; i < counts; i++) {
if (adrs[i].is_internal) continue;
- std::cout << adrs[i].name << std::endl;
InetNtop(PF_INET, &(adrs[i].netmask.netmask4.sin_addr.s_addr), ip,
sizeof(ip) - 1);
ip[49] = '\0';
- std::cout << ip << std::endl;
InetNtop(PF_INET, &(adrs[i].address.address4.sin_addr.s_addr), ip,
sizeof(ip) - 1);
ip[49] = '\0';
- std::cout << ip << std::endl;
addresses.emplace_back(std::string{ip});
}
uv_free_interface_addresses(adrs, counts);
- std::cout << "finished\n";
-
return addresses;
-
- PIP_ADAPTER_ADDRESSES pAddresses = NULL;
- PIP_ADAPTER_ADDRESSES pCurrAddresses = NULL;
- PIP_ADAPTER_UNICAST_ADDRESS pUnicast = NULL;
- PIP_ADAPTER_ANYCAST_ADDRESS pAnycast = NULL;
- PIP_ADAPTER_MULTICAST_ADDRESS pMulticast = NULL;
- unsigned int i = 0;
-
- ULONG outBufLen = 0;
- ULONG Iterations = 0;
- DWORD dwRetVal = 0;
-
- // Allocate a 15 KB buffer to start with.
- outBufLen = WORKING_BUFFER_SIZE;
-
- do {
- pAddresses = reinterpret_cast<IP_ADAPTER_ADDRESSES*>(MALLOC(outBufLen));
- if (pAddresses == NULL) {
- std::printf("Memory allocation failed for IP_ADAPTER_ADDRESSES struct\n");
- std::exit(1);
- }
-
- dwRetVal = GetAdaptersAddresses(AF_INET, GAA_FLAG_INCLUDE_PREFIX, NULL,
- pAddresses, &outBufLen);
-
- if (dwRetVal == ERROR_BUFFER_OVERFLOW) {
- FREE(pAddresses);
- pAddresses = NULL;
- } else {
- break;
- }
-
- Iterations++;
- } while ((dwRetVal == ERROR_BUFFER_OVERFLOW) && (Iterations < MAX_TRIES));
-
- if (dwRetVal == NO_ERROR) {
- pCurrAddresses = pAddresses;
- while (pCurrAddresses) {
- pUnicast = pCurrAddresses->FirstUnicastAddress;
- while (pUnicast != NULL) {
- sockaddr_in* address =
- reinterpret_cast<sockaddr_in*>(pUnicast->Address.lpSockaddr);
- InetNtop(PF_INET, &(address->sin_addr.s_addr), ip, sizeof(ip) - 1);
- ip[49] = '\0';
- addresses.emplace_back(std::string{ip});
- pUnicast = pUnicast->Next;
- }
-
- pCurrAddresses = pCurrAddresses->Next;
- }
- }
-
- if (pAddresses) {
- FREE(pAddresses);
- }
-
- return addresses; // TODO
}
} // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.cpp
index 5ec4c84..e45f361 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.cpp
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.cpp
@@ -450,6 +450,15 @@
return false;
}
+ CS_Status st = 0;
+ auto devices = EnumerateUsbCameras(&st);
+
+ for (auto&& device : devices) {
+ if (device.path == m_path) {
+ SetDescription(device.name);
+ }
+ }
+
if (!m_properties_cached) {
SDEBUG3("caching properties");
DeviceCacheProperties();
@@ -488,21 +497,32 @@
return true;
}
-void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_,
- tagVideoProcAmpProperty tag,
- IAMVideoProcAmp* pProcAmp) {
+template <typename TagProperty, typename IAM>
+void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_, TagProperty tag,
+ IAM* pProcAmp) {
// First see if properties exist
bool isValid = false;
auto property = std::make_unique<UsbCameraProperty>(name_, tag, false,
pProcAmp, &isValid);
if (isValid) {
- DeviceCacheProperty(std::move(property), pProcAmp);
+ DeviceCacheProperty(std::move(property), m_sourceReader.Get());
}
}
+template void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_,
+ tagVideoProcAmpProperty tag,
+ IAMVideoProcAmp* pProcAmp);
+
+template void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_,
+ tagCameraControlProperty tag,
+ IAMCameraControl* pProcAmp);
+
#define CREATEPROPERTY(val) \
DeviceAddProperty(#val, VideoProcAmp_##val, pProcAmp);
+#define CREATECONTROLPROPERTY(val) \
+ DeviceAddProperty(#val, CameraControl_##val, pCamControl);
+
void UsbCameraImpl::DeviceCacheProperties() {
if (!m_sourceReader) return;
@@ -523,6 +543,21 @@
CREATEPROPERTY(Gain)
pProcAmp->Release();
}
+
+ IAMCameraControl* pCamControl = NULL;
+
+ if (SUCCEEDED(m_sourceReader->GetServiceForStream(
+ (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+ IID_PPV_ARGS(&pCamControl)))) {
+ CREATECONTROLPROPERTY(Pan)
+ CREATECONTROLPROPERTY(Tilt)
+ CREATECONTROLPROPERTY(Roll)
+ CREATECONTROLPROPERTY(Zoom)
+ CREATECONTROLPROPERTY(Exposure)
+ CREATECONTROLPROPERTY(Iris)
+ CREATECONTROLPROPERTY(Focus)
+ pCamControl->Release();
+ }
}
int UsbCameraImpl::RawToPercentage(const UsbCameraProperty& rawProp,
@@ -538,7 +573,7 @@
}
void UsbCameraImpl::DeviceCacheProperty(
- std::unique_ptr<UsbCameraProperty> rawProp, IAMVideoProcAmp* pProcAmp) {
+ std::unique_ptr<UsbCameraProperty> rawProp, IMFSourceReader* pProcAmp) {
// For percentage properties, we want to cache both the raw and the
// percentage versions. This function is always called with prop being
// the raw property (as it's coming from the camera) so if required, we need
@@ -707,16 +742,7 @@
if (!prop->device) {
if (prop->id == kPropConnectVerboseId) m_connectVerbose = value;
} else {
- IAMVideoProcAmp* pProcAmp = NULL;
- if (SUCCEEDED(m_sourceReader->GetServiceForStream(
- (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
- IID_PPV_ARGS(&pProcAmp)))) {
- if (!prop->DeviceSet(lock, pProcAmp, value)) {
- pProcAmp->Release();
- return CS_PROPERTY_WRITE_FAILED;
- }
- pProcAmp->Release();
- } else {
+ if (!prop->DeviceSet(lock, m_sourceReader.Get())) {
return CS_PROPERTY_WRITE_FAILED;
}
}
@@ -933,9 +959,7 @@
// Ensure we are initialized by grabbing the message pump
// GetMessagePump();
- ComPtr<IMFMediaSource> ppSource;
std::wstring_convert<std::codecvt_utf8<wchar_t>> utf8_conv;
- ComPtr<IMFMediaSource> pSource;
ComPtr<IMFAttributes> pAttributes;
IMFActivate** ppDevices = nullptr;
@@ -988,7 +1012,6 @@
}
}
CoTaskMemFree(ppDevices);
- pSource.Reset();
return retval;
}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.h
index 5b730fb..4013cda 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.h
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.h
@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
+/* Copyright (c) 2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
@@ -132,11 +132,12 @@
CS_StatusValue DeviceSetMode();
void DeviceCacheMode();
void DeviceCacheProperty(std::unique_ptr<UsbCameraProperty> rawProp,
- IAMVideoProcAmp* pProcAmp);
+ IMFSourceReader* sourceReader);
void DeviceCacheProperties();
void DeviceCacheVideoModes();
- void DeviceAddProperty(const wpi::Twine& name_, tagVideoProcAmpProperty tag,
- IAMVideoProcAmp* pProcAmp);
+ template <typename TagProperty, typename IAM>
+ void DeviceAddProperty(const wpi::Twine& name_, TagProperty tag,
+ IAM* pProcAmp);
ComPtr<IMFMediaType> DeviceCheckModeValid(const VideoMode& toCheck);
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.cpp b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.cpp
index 73bc6c0..ee4198b 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.cpp
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.cpp
@@ -7,13 +7,16 @@
#include "UsbCameraProperty.h"
+#include "ComPtr.h"
+
using namespace cs;
UsbCameraProperty::UsbCameraProperty(const wpi::Twine& name_,
tagVideoProcAmpProperty tag, bool autoProp,
IAMVideoProcAmp* pProcAmp, bool* isValid)
: PropertyImpl{autoProp ? name_ + "_auto" : name_} {
- this->tag = tag;
+ this->tagVideoProc = tag;
+ this->isControlProperty = false;
this->isAutoProp = autoProp;
long paramVal, paramFlag; // NOLINT(runtime/int)
HRESULT hr;
@@ -42,7 +45,7 @@
lock.unlock();
long newValue = 0, paramFlag = 0; // NOLINT(runtime/int)
- if (SUCCEEDED(pProcAmp->Get(tag, &newValue, ¶mFlag))) {
+ if (SUCCEEDED(pProcAmp->Get(tagVideoProc, &newValue, ¶mFlag))) {
lock.lock();
value = newValue;
return true;
@@ -60,10 +63,127 @@
if (!pProcAmp) return true;
lock.unlock();
- if (SUCCEEDED(pProcAmp->Set(tag, newValue, VideoProcAmp_Flags_Manual))) {
+ if (SUCCEEDED(
+ pProcAmp->Set(tagVideoProc, newValue, VideoProcAmp_Flags_Manual))) {
lock.lock();
return true;
}
return false;
}
+
+UsbCameraProperty::UsbCameraProperty(const wpi::Twine& name_,
+ tagCameraControlProperty tag,
+ bool autoProp, IAMCameraControl* pProcAmp,
+ bool* isValid)
+ : PropertyImpl{autoProp ? name_ + "_auto" : name_} {
+ this->tagCameraControl = tag;
+ this->isControlProperty = true;
+ this->isAutoProp = autoProp;
+ long paramVal, paramFlag; // NOLINT(runtime/int)
+ HRESULT hr;
+ long minVal, maxVal, stepVal; // NOLINT(runtime/int)
+ hr = pProcAmp->GetRange(tag, &minVal, &maxVal, &stepVal, ¶mVal,
+ ¶mFlag); // Unable to get the property, trying to
+ // return default value
+ if (SUCCEEDED(hr)) {
+ minimum = minVal;
+ maximum = maxVal;
+ hasMaximum = true;
+ hasMinimum = true;
+ defaultValue = paramVal;
+ step = stepVal;
+ value = paramVal;
+ propKind = CS_PropertyKind::CS_PROP_INTEGER;
+ *isValid = true;
+ } else {
+ *isValid = false;
+ }
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
+ IAMCameraControl* pProcAmp) {
+ if (!pProcAmp) return true;
+
+ lock.unlock();
+ long newValue = 0, paramFlag = 0; // NOLINT(runtime/int)
+ if (SUCCEEDED(pProcAmp->Get(tagCameraControl, &newValue, ¶mFlag))) {
+ lock.lock();
+ value = newValue;
+ return true;
+ }
+
+ return false;
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IAMCameraControl* pProcAmp) const {
+ return DeviceSet(lock, pProcAmp, value);
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IAMCameraControl* pProcAmp,
+ int newValue) const {
+ if (!pProcAmp) return true;
+
+ lock.unlock();
+ if (SUCCEEDED(pProcAmp->Set(tagCameraControl, newValue,
+ CameraControl_Flags_Manual))) {
+ lock.lock();
+ return true;
+ }
+
+ return false;
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock,
+ IMFSourceReader* sourceReader) {
+ if (!sourceReader) return true;
+
+ if (isControlProperty) {
+ ComPtr<IAMCameraControl> pProcAmp;
+ if (SUCCEEDED(sourceReader->GetServiceForStream(
+ (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+ IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+ return DeviceGet(lock, pProcAmp.Get());
+ } else {
+ return false;
+ }
+ } else {
+ ComPtr<IAMVideoProcAmp> pProcAmp;
+ if (SUCCEEDED(sourceReader->GetServiceForStream(
+ (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+ IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+ return DeviceGet(lock, pProcAmp.Get());
+ } else {
+ return false;
+ }
+ }
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IMFSourceReader* sourceReader) const {
+ return DeviceSet(lock, sourceReader, value);
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IMFSourceReader* sourceReader,
+ int newValue) const {
+ if (!sourceReader) return true;
+
+ if (isControlProperty) {
+ ComPtr<IAMCameraControl> pProcAmp;
+ if (SUCCEEDED(sourceReader->GetServiceForStream(
+ (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+ IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+ return DeviceSet(lock, pProcAmp.Get(), newValue);
+ } else {
+ return false;
+ }
+ } else {
+ ComPtr<IAMVideoProcAmp> pProcAmp;
+ if (SUCCEEDED(sourceReader->GetServiceForStream(
+ (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+ IID_PPV_ARGS(pProcAmp.GetAddressOf())))) {
+ return DeviceSet(lock, pProcAmp.Get(), newValue);
+ } else {
+ return false;
+ }
+ }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.h b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.h
index 5d63c73..68795fc 100644
--- a/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.h
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.h
@@ -7,6 +7,10 @@
#pragma once
+#include <mfapi.h>
+#include <mfidl.h>
+#include <mfreadwrite.h>
+
#include <memory>
#include <Dshow.h>
@@ -49,16 +53,23 @@
UsbCameraProperty(const wpi::Twine& name_, tagVideoProcAmpProperty tag,
bool autoProp, IAMVideoProcAmp* pProcAmp, bool* isValid);
- bool DeviceGet(std::unique_lock<wpi::mutex>& lock, IAMVideoProcAmp* pProcAmp);
+ UsbCameraProperty(const wpi::Twine& name_, tagCameraControlProperty tag,
+ bool autoProp, IAMCameraControl* pProcAmp, bool* isValid);
+
+ bool DeviceGet(std::unique_lock<wpi::mutex>& lock,
+ IMFSourceReader* sourceReader);
bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
- IAMVideoProcAmp* pProcAmp) const;
- bool DeviceSet(std::unique_lock<wpi::mutex>& lock, IAMVideoProcAmp* pProcAmp,
- int newValue) const;
+ IMFSourceReader* sourceReader) const;
+ bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IMFSourceReader* sourceReader, int newValue) const;
// If this is a device (rather than software) property
bool device{true};
bool isAutoProp{true};
- tagVideoProcAmpProperty tag;
+
+ bool isControlProperty{false};
+ tagVideoProcAmpProperty tagVideoProc;
+ tagCameraControlProperty tagCameraControl;
// If this is a percentage (rather than raw) property
bool percentage{false};
@@ -68,5 +79,19 @@
unsigned id{0}; // implementation-level id
int type{0}; // implementation type, not CS_PropertyKind!
+
+ private:
+ bool DeviceGet(std::unique_lock<wpi::mutex>& lock,
+ IAMCameraControl* pProcAmp);
+ bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IAMCameraControl* pProcAmp) const;
+ bool DeviceSet(std::unique_lock<wpi::mutex>& lock, IAMCameraControl* pProcAmp,
+ int newValue) const;
+
+ bool DeviceGet(std::unique_lock<wpi::mutex>& lock, IAMVideoProcAmp* pProcAmp);
+ bool DeviceSet(std::unique_lock<wpi::mutex>& lock,
+ IAMVideoProcAmp* pProcAmp) const;
+ bool DeviceSet(std::unique_lock<wpi::mutex>& lock, IAMVideoProcAmp* pProcAmp,
+ int newValue) const;
};
} // namespace cs
diff --git a/third_party/allwpilib_2019/docs/build.gradle b/third_party/allwpilib_2019/docs/build.gradle
index 9f6995f..5bf8dd4 100644
--- a/third_party/allwpilib_2019/docs/build.gradle
+++ b/third_party/allwpilib_2019/docs/build.gradle
@@ -112,6 +112,19 @@
source configurations.javaSource.collect { zipTree(it) }
include '**/*.java'
failOnError = true
+
+ title = "WPILib API $pubVersion"
+ ext.entryPoint = "$destinationDir/index.html"
+
+ if (JavaVersion.current().isJava11Compatible()) {
+ options.addBooleanOption('-no-module-directories', true)
+ doLast {
+ // This is a work-around for https://bugs.openjdk.java.net/browse/JDK-8211194. Can be removed once that issue is fixed on JDK's side
+ // Since JDK 11, package-list is missing from javadoc output files and superseded by element-list file, but a lot of external tools still need it
+ // Here we generate this file manually
+ new File(destinationDir, 'package-list').text = new File(destinationDir, 'element-list').text
+ }
+ }
}
tasks.register("zipJavaDocs", Zip) {
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.cpp
index 1db6c7e..bdba75b 100644
--- a/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.cpp
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.cpp
@@ -145,7 +145,7 @@
return true;
} else if (isHandleType(digitalSourceHandle, HAL_HandleEnum::DIO)) {
int32_t index = getHandleIndex(digitalSourceHandle);
- if (index > kNumDigitalHeaders + kNumDigitalMXPChannels) {
+ if (index >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
// channels 10-15, so need to add headers to remap index
channel = remapSPIChannel(index) + kNumDigitalHeaders;
module = 0;
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/PDP.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/PDP.cpp
index ff1eb81..22ea8c1 100644
--- a/third_party/allwpilib_2019/hal/src/main/native/athena/PDP.cpp
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/PDP.cpp
@@ -9,6 +9,8 @@
#include <memory>
+#include <wpi/mutex.h>
+
#include "HALInitializer.h"
#include "PortsInternal.h"
#include "hal/CANAPI.h"
@@ -106,9 +108,16 @@
} bits;
};
+static wpi::mutex pdpHandleMutex;
+static HAL_PDPHandle pdpHandles[kNumPDPModules];
+
namespace hal {
namespace init {
-void InitializePDP() {}
+void InitializePDP() {
+ for (int i = 0; i < kNumPDPModules; i++) {
+ pdpHandles[i] = HAL_kInvalidHandle;
+ }
+}
} // namespace init
} // namespace hal
@@ -121,6 +130,13 @@
return HAL_kInvalidHandle;
}
+ std::lock_guard<wpi::mutex> lock(pdpHandleMutex);
+
+ if (pdpHandles[module] != HAL_kInvalidHandle) {
+ *status = 0;
+ return pdpHandles[module];
+ }
+
auto handle = HAL_InitializeCAN(manufacturer, module, deviceType, status);
if (*status != 0) {
@@ -128,10 +144,21 @@
return HAL_kInvalidHandle;
}
+ pdpHandles[module] = handle;
+
return handle;
}
-void HAL_CleanPDP(HAL_PDPHandle handle) { HAL_CleanCAN(handle); }
+void HAL_CleanPDP(HAL_PDPHandle handle) {
+ HAL_CleanCAN(handle);
+
+ for (int i = 0; i < kNumPDPModules; i++) {
+ if (pdpHandles[i] == handle) {
+ pdpHandles[i] = HAL_kInvalidHandle;
+ return;
+ }
+ }
+}
HAL_Bool HAL_CheckPDPModule(int32_t module) {
return module < kNumPDPModules && module >= 0;
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.cpp
index 72eb22c..92d09b4 100644
--- a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.cpp
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.cpp
@@ -127,7 +127,7 @@
ThrowUncleanStatusException(env, buf.c_str(), status);
} else {
std::string func;
- auto stack = GetJavaStackTrace(env, &func, "edu.wpi.first.wpilibj");
+ auto stack = GetJavaStackTrace(env, &func, "edu.wpi.first");
HAL_SendError(1, status, 0, message, func.c_str(), stack.c_str(), 1);
}
}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_load.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_load.cpp
index c05e029..3716412 100644
--- a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_load.cpp
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_load.cpp
@@ -109,10 +109,6 @@
continue;
}
switch (*++s) {
- case '\\':
- case '"':
- buf.push_back(s[-1]);
- break;
case 't':
buf.push_back('\t');
break;
@@ -133,7 +129,7 @@
break;
}
default:
- buf.push_back(s[-1]);
+ buf.push_back(*s);
break;
}
}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.cpp
index 5a6982b..47c1096 100644
--- a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.cpp
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.cpp
@@ -90,6 +90,7 @@
storage.SetEntryTypeValue("string/normal", Value::MakeString("hello"));
storage.SetEntryTypeValue("string/special",
Value::MakeString(StringRef("\0\3\5\n", 4)));
+ storage.SetEntryTypeValue("string/quoted", Value::MakeString("\"a\""));
storage.SetEntryTypeValue("raw/empty", Value::MakeRaw(""));
storage.SetEntryTypeValue("raw/normal", Value::MakeRaw("hello"));
storage.SetEntryTypeValue("raw/special",
@@ -599,6 +600,8 @@
std::tie(line, rem) = rem.split('\n');
ASSERT_EQ("string \"string/normal\"=\"hello\"", line);
std::tie(line, rem) = rem.split('\n');
+ ASSERT_EQ("string \"string/quoted\"=\"\\\"a\\\"\"", line);
+ std::tie(line, rem) = rem.split('\n');
ASSERT_EQ("string \"string/special\"=\"\\x00\\x03\\x05\\n\"", line);
std::tie(line, rem) = rem.split('\n');
ASSERT_EQ("array string \"stringarr/empty\"=", line);
@@ -787,18 +790,19 @@
in += "string \"string/empty\"=\"\"\n";
in += "string \"string/normal\"=\"hello\"\n";
in += "string \"string/special\"=\"\\x00\\x03\\x05\\n\"\n";
+ in += "string \"string/quoted\"=\"\\\"a\\\"\"\n";
in += "array string \"stringarr/empty\"=\n";
in += "array string \"stringarr/one\"=\"hello\"\n";
in += "array string \"stringarr/two\"=\"hello\",\"world\\n\"\n";
- EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(22);
+ EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(23);
EXPECT_CALL(notifier,
NotifyEntry(_, _, _, NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX))
- .Times(22);
+ .Times(23);
wpi::raw_mem_istream iss(in);
EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
- ASSERT_EQ(22u, entries().size());
+ ASSERT_EQ(23u, entries().size());
EXPECT_EQ(*Value::MakeBoolean(true), *storage.GetEntryValue("boolean/true"));
EXPECT_EQ(*Value::MakeBoolean(false),
@@ -811,6 +815,8 @@
*storage.GetEntryValue("string/normal"));
EXPECT_EQ(*Value::MakeString(StringRef("\0\3\5\n", 4)),
*storage.GetEntryValue("string/special"));
+ EXPECT_EQ(*Value::MakeString("\"a\""),
+ *storage.GetEntryValue("string/quoted"));
EXPECT_EQ(*Value::MakeRaw(""), *storage.GetEntryValue("raw/empty"));
EXPECT_EQ(*Value::MakeRaw("hello"), *storage.GetEntryValue("raw/normal"));
EXPECT_EQ(*Value::MakeRaw(StringRef("\0\3\5\n", 4)),
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
index 92f1720..ead2534 100644
--- a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
@@ -96,7 +96,7 @@
int numBytes = (buttonCount + 7) / 8;
stick.buttons.buttons = 0;
for (int i = 0; i < numBytes; i++) {
- stick.buttons.buttons |= dataInput[1 + i] << (8 * (i));
+ stick.buttons.buttons |= dataInput[numBytes - i] << (8 * (i));
}
stick.buttons.count = buttonCount;
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
index a72aafc..c1fc293 100644
--- a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
@@ -66,13 +66,21 @@
TEST_F(DSCommPacketTest, MainJoystickTag) {
for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+ // Just random data
+ std::array<uint8_t, 12> _buttons{{0, 1, 0, 0, 1, 1, 0, 1, 0, 1, 0, 1}};
+
+ std::array<uint8_t, 2> _button_bytes{{0, 0}};
+ for (int btn = 0; btn < 8; btn++) _button_bytes[1] |= _buttons[btn] << btn;
+ for (int btn = 8; btn < 12; btn++)
+ _button_bytes[0] |= _buttons[btn] << (btn - 8);
+
// 5 for base, 4 joystick, 12 buttons (2 bytes) 3 povs
uint8_t arr[5 + 4 + 2 + 6] = {// Size, Tag
16, 12,
// Axes
4, 0x9C, 0xCE, 0, 75,
- // Buttons
- 12, 0xFF, 0x0F,
+ // Buttons (LSB 0)
+ 12, _button_bytes[0], _button_bytes[1],
// POVs
3, 0, 50, 0, 100, 0x0F, 0x00};
@@ -80,6 +88,11 @@
ASSERT_EQ(data.axes.count, 4);
ASSERT_EQ(data.povs.count, 3);
ASSERT_EQ(data.buttons.count, 12);
+
+ for (int btn = 0; btn < 12; btn++) {
+ ASSERT_EQ((data.buttons.buttons & (1 << btn)) != 0, _buttons[btn] != 0)
+ << "Button " << btn;
+ }
}
}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
index 771d81f..0de2004 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
@@ -26,29 +26,29 @@
m_watchdog(period, [this] { PrintLoopOverrunMessage(); }) {}
void IterativeRobotBase::RobotInit() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void IterativeRobotBase::DisabledInit() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void IterativeRobotBase::AutonomousInit() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void IterativeRobotBase::TeleopInit() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void IterativeRobotBase::TestInit() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void IterativeRobotBase::RobotPeriodic() {
static bool firstRun = true;
if (firstRun) {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
firstRun = false;
}
}
@@ -56,7 +56,7 @@
void IterativeRobotBase::DisabledPeriodic() {
static bool firstRun = true;
if (firstRun) {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
firstRun = false;
}
}
@@ -64,7 +64,7 @@
void IterativeRobotBase::AutonomousPeriodic() {
static bool firstRun = true;
if (firstRun) {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
firstRun = false;
}
}
@@ -72,7 +72,7 @@
void IterativeRobotBase::TeleopPeriodic() {
static bool firstRun = true;
if (firstRun) {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
firstRun = false;
}
}
@@ -80,7 +80,7 @@
void IterativeRobotBase::TestPeriodic() {
static bool firstRun = true;
if (firstRun) {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
firstRun = false;
}
}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SampleRobot.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SampleRobot.cpp
index 338f7be..190f5d8 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SampleRobot.cpp
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SampleRobot.cpp
@@ -59,23 +59,23 @@
}
void SampleRobot::RobotInit() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::Disabled() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::Autonomous() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::OperatorControl() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::Test() {
- wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+ wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
}
void SampleRobot::RobotMain() { m_robotMainOverridden = false; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Watchdog.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Watchdog.cpp
index b67f94d..f7c1778 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Watchdog.cpp
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Watchdog.cpp
@@ -18,7 +18,7 @@
class Watchdog::Thread : public wpi::SafeThread {
public:
template <typename T>
- struct DerefGreater : public std::binary_function<T, T, bool> {
+ struct DerefGreater {
constexpr bool operator()(const T& lhs, const T& rhs) const {
return *lhs > *rhs;
}
@@ -160,8 +160,6 @@
auto thr = m_owner->GetThread();
if (!thr) return;
- m_isExpired = false;
-
thr->m_watchdogs.remove(this);
thr->m_cond.notify_all();
}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInLayouts.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInLayouts.cpp
deleted file mode 100644
index 5d09310..0000000
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInLayouts.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) 2018 FIRST. All Rights Reserved. */
-/* Open Source Software - may be modified and shared by FRC teams. The code */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project. */
-/*----------------------------------------------------------------------------*/
-
-#include "frc/shuffleboard/BuiltInLayouts.h"
-
-using namespace frc;
-
-const LayoutType BuiltInLayouts::kList{"List Layout"};
-const LayoutType BuiltInLayouts::kGrid{"Grid Layout"};
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInWidgets.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInWidgets.cpp
deleted file mode 100644
index df6a1f3..0000000
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInWidgets.cpp
+++ /dev/null
@@ -1,35 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) 2018 FIRST. All Rights Reserved. */
-/* Open Source Software - may be modified and shared by FRC teams. The code */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project. */
-/*----------------------------------------------------------------------------*/
-
-#include "frc/shuffleboard/BuiltInWidgets.h"
-
-using namespace frc;
-
-const WidgetType BuiltInWidgets::kTextView{"Text View"};
-const WidgetType BuiltInWidgets::kNumberSlider{"Number Slider"};
-const WidgetType BuiltInWidgets::kNumberBar{"Number Bar"};
-const WidgetType BuiltInWidgets::kDial{"Simple Dial"};
-const WidgetType BuiltInWidgets::kGraph{"Graph"};
-const WidgetType BuiltInWidgets::kBooleanBox{"Boolean Box"};
-const WidgetType BuiltInWidgets::kToggleButton{"Toggle Button"};
-const WidgetType BuiltInWidgets::kToggleSwitch{"Toggle Switch"};
-const WidgetType BuiltInWidgets::kVoltageView{"Voltage View"};
-const WidgetType BuiltInWidgets::kPowerDistributionPanel{"PDP"};
-const WidgetType BuiltInWidgets::kComboBoxChooser{"ComboBox Chooser"};
-const WidgetType BuiltInWidgets::kSplitButtonChooser{"Split Button Chooser"};
-const WidgetType BuiltInWidgets::kEncoder{"Encoder"};
-const WidgetType BuiltInWidgets::kSpeedController{"Speed Controller"};
-const WidgetType BuiltInWidgets::kCommand{"Command"};
-const WidgetType BuiltInWidgets::kPIDCommand{"PID Command"};
-const WidgetType BuiltInWidgets::kPIDController{"PID Controller"};
-const WidgetType BuiltInWidgets::kAccelerometer{"Accelerometer"};
-const WidgetType BuiltInWidgets::k3AxisAccelerometer{"3-Axis Accelerometer"};
-const WidgetType BuiltInWidgets::kGyro{"Gyro"};
-const WidgetType BuiltInWidgets::kRelay{"Relay"};
-const WidgetType BuiltInWidgets::kDifferentialDrive{"Differential Drivebase"};
-const WidgetType BuiltInWidgets::kMecanumDrive{"Mecanum Drivebase"};
-const WidgetType BuiltInWidgets::kCameraStream{"Camera Stream"};
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
index 4954cff..f13116d 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
@@ -18,6 +18,12 @@
using namespace frc;
+static constexpr const char* layoutStrings[] = {"List Layout", "Grid Layout"};
+
+static constexpr const char* GetStringFromBuiltInLayout(BuiltInLayouts layout) {
+ return layoutStrings[static_cast<int>(layout)];
+}
+
ShuffleboardContainer::ShuffleboardContainer(const wpi::Twine& title)
: ShuffleboardValue(title) {}
@@ -27,6 +33,11 @@
}
ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
+ BuiltInLayouts type) {
+ return GetLayout(title, GetStringFromBuiltInLayout(type));
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
const LayoutType& type) {
return GetLayout(title, type.GetLayoutName());
}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
new file mode 100644
index 0000000..4573516
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+
+using namespace frc;
+
+static constexpr const char* widgetStrings[] = {
+ "Text View",
+ "Number Slider",
+ "Number Bar",
+ "Simple Dial",
+ "Graph",
+ "Boolean Box",
+ "Toggle Button",
+ "Toggle Switch",
+ "Voltage View",
+ "PDP",
+ "ComboBox Chooser",
+ "Split Button Chooser",
+ "Encoder",
+ "Speed Controller",
+ "Command",
+ "PID Command",
+ "PID Controller",
+ "Accelerometer",
+ "3-Axis Accelerometer",
+ "Gyro",
+ "Relay",
+ "Differential Drivebase",
+ "Mecanum Drivebase",
+ "Camera Stream",
+};
+
+const char* detail::GetStringForWidgetType(BuiltInWidgets type) {
+ return widgetStrings[static_cast<int>(type)];
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Filesystem.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Filesystem.h
index baf8044..d7675d6 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Filesystem.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Filesystem.h
@@ -12,6 +12,7 @@
#include "frc/RobotBase.h"
namespace frc {
+/** WPILib FileSystem namespace */
namespace filesystem {
/**
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h
index 6a61b87..c958baa 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h
@@ -19,8 +19,7 @@
* .GetLayout(BuiltinLayouts::kList, "My List");
* }</pre>
*/
-class BuiltInLayouts {
- public:
+enum class BuiltInLayouts {
/**
* Groups components in a vertical list. New widgets added to the layout will
* be placed at the bottom of the list. <br>Custom properties: <table>
@@ -30,7 +29,7 @@
* {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td></tr>
* </table>
*/
- static const LayoutType kList;
+ kList,
/**
* Groups components in an <i>n</i> x <i>m</i> grid. Grid layouts default to
@@ -47,7 +46,7 @@
* </tr>
* </table>
*/
- static const LayoutType kGrid;
+ kGrid
};
} // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h
index 1fd720f..bdd2011 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h
@@ -25,8 +25,7 @@
* <p>Each value in this enum goes into detail on what data types that widget
* can support, as well as the custom properties that widget uses.
*/
-class BuiltInWidgets {
- public:
+enum class BuiltInWidgets {
/**
* Displays a value with a simple text field.
* <br>Supported types:
@@ -37,7 +36,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kTextView;
+ kTextView,
/**
* Displays a number with a controllable slider.
* <br>Supported types:
@@ -54,7 +53,7 @@
* slider by with the arrow keys</td></tr>
* </table>
*/
- static const WidgetType kNumberSlider;
+ kNumberSlider,
/**
* Displays a number with a view-only bar.
* <br>Supported types:
@@ -71,7 +70,7 @@
* of the bar</td></tr>
* </table>
*/
- static const WidgetType kNumberBar;
+ kNumberBar,
/**
* Displays a number with a view-only dial. Displayed values are rounded to
* the nearest integer. <br>Supported types: <ul> <li>Number</li>
@@ -86,7 +85,7 @@
* value as text</td></tr>
* </table>
*/
- static const WidgetType kDial;
+ kDial,
/**
* Displays a number with a graph. <strong>NOTE:</strong> graphs can be taxing
* on the computer running the dashboard. Keep the number of visible data
@@ -103,7 +102,7 @@
* <td>How long, in seconds, should past data be visible for</td></tr>
* </table>
*/
- static const WidgetType kGraph;
+ kGraph,
/**
* Displays a boolean value as a large colored box.
* <br>Supported types:
@@ -121,7 +120,7 @@
* <td>Can be specified as a string or a number</td></tr>
* </table>
*/
- static const WidgetType kBooleanBox;
+ kBooleanBox,
/**
* Displays a boolean with a large interactive toggle button.
* <br>Supported types:
@@ -130,7 +129,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kToggleButton;
+ kToggleButton,
/**
* Displays a boolean with a fixed-size toggle switch.
* <br>Supported types:
@@ -139,7 +138,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kToggleSwitch;
+ kToggleSwitch,
/**
* Displays an analog input or a raw number with a number bar.
* <br>Supported types:
@@ -162,7 +161,7 @@
* bar</td></tr>
* </table>
*/
- static const WidgetType kVoltageView;
+ kVoltageView,
/**
* Displays a {@link edu.wpi.first.wpilibj.PowerDistributionPanel
* PowerDistributionPanel}. <br>Supported types: <ul> <li>{@link
@@ -175,7 +174,7 @@
* <td>Whether or not to display the voltage and current draw</td></tr>
* </table>
*/
- static const WidgetType kPowerDistributionPanel;
+ kPowerDistributionPanel,
/**
* Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser
* SendableChooser} with a dropdown combo box with a list of options.
@@ -185,7 +184,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kComboBoxChooser;
+ kComboBoxChooser,
/**
* Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser
* SendableChooser} with a toggle button for each available option.
@@ -195,7 +194,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kSplitButtonChooser;
+ kSplitButtonChooser,
/**
* Displays an {@link edu.wpi.first.wpilibj.Encoder} displaying its speed,
* total travelled distance, and its distance per tick. <br>Supported types:
@@ -204,7 +203,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kEncoder;
+ kEncoder,
/**
* Displays a {@link edu.wpi.first.wpilibj.SpeedController SpeedController}.
* The speed controller will be controllable from the dashboard when test mode
@@ -228,7 +227,7 @@
* <td>One of {@code ["HORIZONTAL", "VERTICAL"]}</td></tr>
* </table>
*/
- static const WidgetType kSpeedController;
+ kSpeedController,
/**
* Displays a command with a toggle button. Pressing the button will start the
* command, and the button will automatically release when the command
@@ -239,7 +238,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kCommand;
+ kCommand,
/**
* Displays a PID command with a checkbox and an editor for the PIDF
* constants. Selecting the checkbox will start the command, and the checkbox
@@ -249,7 +248,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kPIDCommand;
+ kPIDCommand,
/**
* Displays a PID controller with an editor for the PIDF constants and a
* toggle switch for enabling and disabling the controller. <br>Supported
@@ -257,7 +256,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kPIDController;
+ kPIDController,
/**
* Displays an accelerometer with a number bar displaying the magnitude of the
* acceleration and text displaying the exact value. <br>Supported types: <ul>
@@ -278,7 +277,7 @@
* <td>Show or hide the tick marks on the number bars</td></tr>
* </table>
*/
- static const WidgetType kAccelerometer;
+ kAccelerometer,
/**
* Displays a 3-axis accelerometer with a number bar for each axis'
* accleration. <br>Supported types: <ul> <li>{@link
@@ -298,7 +297,7 @@
* <td>Show or hide the tick marks on the number bars</td></tr>
* </table>
*/
- static const WidgetType k3AxisAccelerometer;
+ k3AxisAccelerometer,
/**
* Displays a gyro with a dial from 0 to 360 degrees.
* <br>Supported types:
@@ -317,7 +316,7 @@
* <tr><td>Show tick mark ring</td><td>Boolean</td><td>true</td></tr>
* </table>
*/
- static const WidgetType kGyro;
+ kGyro,
/**
* Displays a relay with toggle buttons for each supported mode (off, on,
* forward, reverse). <br>Supported types: <ul> <li>{@link
@@ -325,7 +324,7 @@
* </ul>
* <br>This widget has no custom properties.
*/
- static const WidgetType kRelay;
+ kRelay,
/**
* Displays a differential drive with a widget that displays the speed of each
* side of the drivebase and a vector for the direction and rotation of the
@@ -344,7 +343,7 @@
* <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
* </table>
*/
- static const WidgetType kDifferentialDrive;
+ kDifferentialDrive,
/**
* Displays a mecanum drive with a widget that displays the speed of each
* wheel, and vectors for the direction and rotation of the drivebase. The
@@ -357,7 +356,7 @@
* <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
* </table>
*/
- static const WidgetType kMecanumDrive;
+ kMecanumDrive,
/**
* Displays a camera stream.
* <br>Supported types:
@@ -381,7 +380,7 @@
* </td></tr>
* </table>
*/
- static const WidgetType kCameraStream;
+ kCameraStream
};
} // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h
index 22fe361..50e448b 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h
@@ -7,7 +7,7 @@
#pragma once
-#include <wpi/Twine.h>
+#include <wpi/StringRef.h>
namespace frc {
@@ -20,7 +20,8 @@
*/
class LayoutType {
public:
- explicit LayoutType(const char* layoutName) : m_layoutName(layoutName) {}
+ explicit constexpr LayoutType(const char* layoutName)
+ : m_layoutName(layoutName) {}
~LayoutType() = default;
/**
@@ -30,7 +31,7 @@
wpi::StringRef GetLayoutName() const;
private:
- wpi::StringRef m_layoutName;
+ const char* m_layoutName;
};
} // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
index e53bcfc..ab03099 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
@@ -20,6 +20,7 @@
#include "frc/ErrorBase.h"
#include "frc/WPIErrors.h"
+#include "frc/shuffleboard/BuiltInLayouts.h"
#include "frc/shuffleboard/LayoutType.h"
#include "frc/shuffleboard/ShuffleboardComponentBase.h"
#include "frc/shuffleboard/ShuffleboardValue.h"
@@ -61,6 +62,16 @@
* @param layoutType the type of the layout, eg "List" or "Grid"
* @return the layout
*/
+ ShuffleboardLayout& GetLayout(const wpi::Twine& title, BuiltInLayouts type);
+
+ /**
+ * Gets the layout with the given type and title, creating it if it does not
+ * already exist at the time this method is called.
+ *
+ * @param title the title of the layout
+ * @param layoutType the type of the layout, eg "List" or "Grid"
+ * @return the layout
+ */
ShuffleboardLayout& GetLayout(const wpi::Twine& title,
const LayoutType& type);
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h
index 2e67160..3b1b0a8 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h
@@ -9,6 +9,7 @@
#include <wpi/Twine.h>
+#include "frc/shuffleboard/BuiltInWidgets.h"
#include "frc/shuffleboard/ShuffleboardComponent.h"
#include "frc/shuffleboard/WidgetType.h"
@@ -16,6 +17,10 @@
class ShuffleboardContainer;
+namespace detail {
+const char* GetStringForWidgetType(BuiltInWidgets type);
+} // namespace detail
+
/**
* Abstract superclass for widgets.
*
@@ -24,12 +29,11 @@
* @tparam Derived the self type
*/
template <typename Derived>
-class ShuffleboardWidget
- : public ShuffleboardComponent<ShuffleboardWidget<Derived>> {
+class ShuffleboardWidget : public ShuffleboardComponent<Derived> {
public:
ShuffleboardWidget(ShuffleboardContainer& parent, const wpi::Twine& title)
: ShuffleboardValue(title),
- ShuffleboardComponent<ShuffleboardWidget<Derived>>(parent, title) {}
+ ShuffleboardComponent<Derived>(parent, title) {}
/**
* Sets the type of widget used to display the data. If not set, the default
@@ -39,7 +43,18 @@
* @return this widget object
* @see BuiltInWidgets
*/
- Derived& withWidget(const WidgetType& widgetType) {
+ Derived& WithWidget(BuiltInWidgets widgetType) {
+ return WithWidget(detail::GetStringForWidgetType(widgetType));
+ }
+
+ /**
+ * Sets the type of widget used to display the data. If not set, the default
+ * widget type will be used.
+ *
+ * @param widgetType the type of the widget used to display the data
+ * @return this widget object
+ */
+ Derived& WithWidget(const WidgetType& widgetType) {
return WithWidget(widgetType.GetWidgetName());
}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h
index f96e9b6..057d594 100644
--- a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h
@@ -7,7 +7,7 @@
#pragma once
-#include <wpi/Twine.h>
+#include <wpi/StringRef.h>
namespace frc {
@@ -20,7 +20,8 @@
*/
class WidgetType {
public:
- explicit WidgetType(const char* widgetName) : m_widgetName(widgetName) {}
+ explicit constexpr WidgetType(const char* widgetName)
+ : m_widgetName(widgetName) {}
~WidgetType() = default;
/**
@@ -30,7 +31,7 @@
wpi::StringRef GetWidgetName() const;
private:
- wpi::StringRef m_widgetName;
+ const char* m_widgetName;
};
} // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/WatchdogTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/WatchdogTest.cpp
index 141c72e..c796116 100644
--- a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/WatchdogTest.cpp
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/WatchdogTest.cpp
@@ -83,11 +83,18 @@
TEST(WatchdogTest, IsExpired) {
Watchdog watchdog(0.2, [] {});
+ EXPECT_FALSE(watchdog.IsExpired());
watchdog.Enable();
EXPECT_FALSE(watchdog.IsExpired());
std::this_thread::sleep_for(std::chrono::milliseconds(300));
EXPECT_TRUE(watchdog.IsExpired());
+
+ watchdog.Disable();
+ EXPECT_TRUE(watchdog.IsExpired());
+
+ watchdog.Reset();
+ EXPECT_FALSE(watchdog.IsExpired());
}
TEST(WatchdogTest, Epochs) {
@@ -118,7 +125,11 @@
EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
}
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_MultiWatchdog) {
+#else
TEST(WatchdogTest, MultiWatchdog) {
+#endif
uint32_t watchdogCounter1 = 0;
uint32_t watchdogCounter2 = 0;
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp
new file mode 100644
index 0000000..3dd9dbf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardWidgetTest.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+#include <array>
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/commands/InstantCommand.h"
+#include "frc/shuffleboard/BuiltInWidgets.h"
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ShuffleboardWidgetTest : public testing::Test {
+ void SetUp() override {
+ m_ntInstance = nt::NetworkTableInstance::Create();
+ m_instance = std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
+ m_tab = &(m_instance->GetTab("Tab"));
+ }
+
+ protected:
+ nt::NetworkTableInstance m_ntInstance;
+ ShuffleboardTab* m_tab;
+ std::unique_ptr<detail::ShuffleboardInstance> m_instance;
+};
+
+TEST_F(ShuffleboardWidgetTest, UseBuiltInWidget) {
+ auto entry =
+ m_tab->Add("Name", "").WithWidget(BuiltInWidgets::kTextView).GetEntry();
+ EXPECT_EQ("/Shuffleboard/Tab/Name", entry.GetName())
+ << "The widget entry has the wrong name";
+}
+
+TEST_F(ShuffleboardWidgetTest, WithProperties) {
+ wpi::StringMap<std::shared_ptr<nt::Value>> properties{
+ std::make_pair("min", nt::Value::MakeDouble(0)),
+ std::make_pair("max", nt::Value::MakeDouble(1))};
+ auto entry =
+ m_tab->Add("WithProperties", "").WithProperties(properties).GetEntry();
+
+ // Update the instance to generate
+ // the metadata entries for the widget properties
+ m_instance->Update();
+
+ auto propertiesTable = m_ntInstance.GetTable(
+ "/Shuffleboard/.metadata/Tab/WithProperties/Properties");
+
+ EXPECT_EQ("/Shuffleboard/Tab/WithProperties", entry.GetName())
+ << "The widget entry has the wrong name";
+ EXPECT_FLOAT_EQ(0, propertiesTable->GetEntry("min").GetDouble(-1))
+ << "The 'min' property should be 0";
+ EXPECT_FLOAT_EQ(1, propertiesTable->GetEntry("max").GetDouble(-1))
+ << "The 'max' property should be 1";
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
index ee13ef9..9dfcb64 100644
--- a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
@@ -86,7 +86,7 @@
* never indicate that the code is ready, causing the robot to be bypassed in a match.
*/
public void robotInit() {
- System.out.println("Default robotInit() method... Overload me!");
+ System.out.println("Default robotInit() method... Override me!");
}
/**
@@ -96,7 +96,7 @@
* robot enters disabled mode.
*/
public void disabledInit() {
- System.out.println("Default disabledInit() method... Overload me!");
+ System.out.println("Default disabledInit() method... Override me!");
}
/**
@@ -106,7 +106,7 @@
* robot enters autonomous mode.
*/
public void autonomousInit() {
- System.out.println("Default autonomousInit() method... Overload me!");
+ System.out.println("Default autonomousInit() method... Override me!");
}
/**
@@ -116,7 +116,7 @@
* robot enters teleop mode.
*/
public void teleopInit() {
- System.out.println("Default teleopInit() method... Overload me!");
+ System.out.println("Default teleopInit() method... Override me!");
}
/**
@@ -127,7 +127,7 @@
*/
@SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
public void testInit() {
- System.out.println("Default testInit() method... Overload me!");
+ System.out.println("Default testInit() method... Override me!");
}
/* ----------- Overridable periodic code ----------------- */
@@ -139,7 +139,7 @@
*/
public void robotPeriodic() {
if (m_rpFirstRun) {
- System.out.println("Default robotPeriodic() method... Overload me!");
+ System.out.println("Default robotPeriodic() method... Override me!");
m_rpFirstRun = false;
}
}
@@ -151,7 +151,7 @@
*/
public void disabledPeriodic() {
if (m_dpFirstRun) {
- System.out.println("Default disabledPeriodic() method... Overload me!");
+ System.out.println("Default disabledPeriodic() method... Override me!");
m_dpFirstRun = false;
}
}
@@ -163,7 +163,7 @@
*/
public void autonomousPeriodic() {
if (m_apFirstRun) {
- System.out.println("Default autonomousPeriodic() method... Overload me!");
+ System.out.println("Default autonomousPeriodic() method... Override me!");
m_apFirstRun = false;
}
}
@@ -175,7 +175,7 @@
*/
public void teleopPeriodic() {
if (m_tpFirstRun) {
- System.out.println("Default teleopPeriodic() method... Overload me!");
+ System.out.println("Default teleopPeriodic() method... Override me!");
m_tpFirstRun = false;
}
}
@@ -188,7 +188,7 @@
@SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
public void testPeriodic() {
if (m_tmpFirstRun) {
- System.out.println("Default testPeriodic() method... Overload me!");
+ System.out.println("Default testPeriodic() method... Override me!");
m_tmpFirstRun = false;
}
}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
index 780a5c2..5b70cd9 100644
--- a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
@@ -667,7 +667,7 @@
*
* @param pidSource the type of input
*/
- void setPIDSourceType(PIDSourceType pidSource) {
+ public void setPIDSourceType(PIDSourceType pidSource) {
m_pidInput.setPIDSourceType(pidSource);
}
@@ -676,7 +676,7 @@
*
* @return the PID controller input type
*/
- PIDSourceType getPIDSourceType() {
+ public PIDSourceType getPIDSourceType() {
return m_pidInput.getPIDSourceType();
}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SampleRobot.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SampleRobot.java
index 6c13013..aac7cad 100644
--- a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SampleRobot.java
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SampleRobot.java
@@ -55,7 +55,7 @@
}
/**
- * Disabled should go here. Users should overload this method to run code that should run while
+ * Disabled should go here. Users should override this method to run code that should run while
* the field is disabled.
*
* <p>Called once each time the robot enters the disabled state.
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
index b42dfdf..8e0b177 100644
--- a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
@@ -46,7 +46,7 @@
// ultrasonic sensor list
private static final List<Ultrasonic> m_sensors = new ArrayList<>();
// automatic round robin mode
- private static boolean m_automaticEnabled;
+ private static volatile boolean m_automaticEnabled;
private DigitalInput m_echoChannel;
private DigitalOutput m_pingChannel;
private boolean m_allocatedChannels;
@@ -70,30 +70,18 @@
private static class UltrasonicChecker extends Thread {
@Override
public synchronized void run() {
- int sensorIndex = 0;
- Ultrasonic ultrasonic;
while (m_automaticEnabled) {
- //lock list to ensure deletion doesn't occur between empty check and retrieving sensor
- synchronized (m_sensors) {
- if (m_sensors.isEmpty()) {
- return;
+ for (Ultrasonic sensor: m_sensors) {
+ if (!m_automaticEnabled) {
+ break;
}
- if (sensorIndex >= m_sensors.size()) {
- sensorIndex = m_sensors.size() - 1;
- }
- ultrasonic = m_sensors.get(sensorIndex);
- }
- if (ultrasonic.isEnabled()) {
- // Do the ping
- ultrasonic.m_pingChannel.pulse(kPingTime);
- }
- if (sensorIndex < m_sensors.size()) {
- sensorIndex++;
- } else {
- sensorIndex = 0;
- }
- Timer.delay(.1); // wait for ping to return
+ if (sensor.isEnabled()) {
+ sensor.m_pingChannel.pulse(kPingTime); // do the ping
+ }
+
+ Timer.delay(0.1); // wait for ping to return
+ }
}
}
}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
index 7ff8937..bc6a844 100644
--- a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
@@ -195,8 +195,6 @@
public void disable() {
m_queueMutex.lock();
try {
- m_isExpired = false;
-
m_watchdogs.remove(this);
m_schedulerWaiter.signalAll();
} finally {
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/WatchdogTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/WatchdogTest.java
index 9ed5db8..09414cf 100644
--- a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/WatchdogTest.java
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/WatchdogTest.java
@@ -121,6 +121,7 @@
void isExpiredTest() {
final Watchdog watchdog = new Watchdog(0.2, () -> {
});
+ assertFalse(watchdog.isExpired());
watchdog.enable();
assertFalse(watchdog.isExpired());
@@ -130,6 +131,12 @@
Thread.currentThread().interrupt();
}
assertTrue(watchdog.isExpired());
+
+ watchdog.disable();
+ assertTrue(watchdog.isExpired());
+
+ watchdog.reset();
+ assertFalse(watchdog.isExpired());
}
@Test
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Pipe.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Pipe.cpp
index 8da7244..8d4ee76 100644
--- a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Pipe.cpp
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Pipe.cpp
@@ -25,8 +25,27 @@
return h;
}
+void Pipe::Reuse(std::function<void()> callback, bool ipc) {
+ if (IsClosing()) return;
+ if (!m_reuseData) m_reuseData = std::make_unique<ReuseData>();
+ m_reuseData->callback = callback;
+ m_reuseData->ipc = ipc;
+ uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+ Pipe& h = *static_cast<Pipe*>(handle->data);
+ if (!h.m_reuseData) return;
+ auto data = std::move(h.m_reuseData);
+ auto err =
+ uv_pipe_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->ipc ? 1 : 0);
+ if (err < 0) {
+ h.ReportError(err);
+ return;
+ }
+ data->callback();
+ });
+}
+
std::shared_ptr<Pipe> Pipe::Accept() {
- auto client = Create(GetLoopRef());
+ auto client = Create(GetLoopRef(), GetRaw()->ipc);
if (!client) return nullptr;
if (!Accept(client)) {
client->Release();
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Pipe.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Pipe.h
index b4d8af2..304ccbb 100644
--- a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Pipe.h
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Pipe.h
@@ -57,6 +57,18 @@
}
/**
+ * Reuse this handle. This closes the handle, and after the close completes,
+ * reinitializes it (identically to Create) and calls the provided callback.
+ * Unlike Close(), it does NOT emit the closed signal, however, IsClosing()
+ * will return true until the callback is called. This does nothing if
+ * IsClosing() is true (e.g. if Close() was called).
+ *
+ * @param ipc IPC
+ * @param callback Callback
+ */
+ void Reuse(std::function<void()> callback, bool ipc = false);
+
+ /**
* Accept incoming connection.
*
* This call is used in conjunction with `Listen()` to accept incoming
@@ -176,6 +188,12 @@
private:
Pipe* DoAccept() override;
+
+ struct ReuseData {
+ std::function<void()> callback;
+ bool ipc;
+ };
+ std::unique_ptr<ReuseData> m_reuseData;
};
/**